๐ก ๋ณธ ๋ฌธ์๋ 'ROS URDF vs. Gazebo SDF: Link Pose, Joint Pose, Visual & Collision'์ ๋ํด ์ ๋ฆฌํด๋์ ๊ธ์ ๋๋ค.
ROS 2 ๋ฐ Gazebo๋ฅผ ์ฌ์ฉํ์ฌ ์๋ฎฌ๋ ์ด์ ์ฉ ๋ก๋ด์ ๋ง๋๋ ๊ฐ์ฅ ํผ๋์ค๋ฌ์ด ๊ฐ๋ ์ค ํ๋ ๋ URDF ๋ฐ SDF๋ฅผ ์ฌ์ฉํ์ฌ ๋ก๋ด์ ๋งํฌ ๋ฐ ๊ด์ ์ ๋ํ ์ขํ ํ๋ ์์ ์ค์ ํ๋ ๋ฐฉ๋ฒ์ ๋๋ค . ์ด ํํ ๋ฆฌ์ผ์์๋ ๋งํฌ์ ๊ด์ ์ ํฌ์ฆ๊ฐ ์ผ๋ฐ์ ์ธ URDF ํ์ผ๊ณผ SDF ํ์ผ ๋ด์์ ์ ์๋๋ ๋ฐฉ์์ ๋น๊ตํ๊ณ ๋์กฐํด ๋ณด๊ฒ ์ต๋๋ค.
1. Prerequisites
๋ฌด์๋ณด๋ค URDF๋ฅผ ์ดํดํ๊ธฐ ์ํด์๋ ๋ชจ๋ฐ์ผ ๋ก๋ด ์ขํ๊ณ๋ฅผ ์ดํดํด์ผํฉ๋๋ค. ํด๋น ๋ด์ฉ์ '[ROS] ROS TF ์ขํ๊ณ ๋ฐ ๋ณํ'์ ์ ๋ฆฌํด๋์์ผ๋ ์ฐธ๊ณ ํ์๊ธฐ ๋ฐ๋๋๋ค.
1) What is a URDF File?
URDF(Unified Robotic Description Format)๋ ROS์์ ๋ก๋ด์ ๋ชจ๋ ์์( ๋งํฌ ๋ฐ ๊ด์ ) ๋ฅผ ์ค๋ช ํ๋ ๋ฐ ์ฌ์ฉ๋๋ XML ํ์ผ ํ์์ ๋๋ค .
์ด ํํ ๋ฆฌ์ผ ์์ URDF๋ก ํํ๋ ๋ก๋ด์ Rviz์ ์ฌ๋ฆฌ๋ ๋ฐฉ๋ฒ์ ์ฐพ์ ์ ์์ต๋๋ค.
2) What is a SDF File?
SDF( Simulation Description Format)๋ ๋ก๋ด์ ๋ชจ๋ ์์( ๋งํฌ ๋ฐ ๊ด์ ) ๋ฅผ ์ค๋ช ํ๊ธฐ ์ํด Gazebo์์ ์ฌ์ฉ๋๋ XML ํ์ผ ํ์์ ๋๋ค .
์ด ํํ ๋ฆฌ์ผ ์์ SDF๋ก ํํ๋ ๋ก๋ด์ Gazebo์ ์ฌ๋ฆฌ๋ ๋ฐฉ๋ฒ์ ์ฐพ์ ์ ์์ต๋๋ค.
2. Concept
URDF๋ฅผ ํตํด ์ฐ๋ฆฌ๋ ์๋์ ๊ฒ๋ค์ ํํํ ์ ์์ต๋๋ค.
- Kinematic and dynamic description of the robot
- Visual representation of the robot
- Collision model of the robot
์ ์ธ๊ฐ์ง๋ ์ดํ XML ์์ฑ์ ์ฃผ๋ก ๋ค๋ฃจ๊ฒ ๋๋ ์ค์ํ ์์๋ค์ ๋๋ค.
์๊ฐํ ์ธ๊ฐ์ง ์์๋ฅผ ๋ง์กฑํ๋ ๊ฐ๋จํ ๋ก๋ด์ ์๋ ์๋ ๊ทธ๋ฆผ์ฒ๋ผ ๋ํ๋ผ ์ ์์ต๋๋ค. ๋ก๋ด์ ๊ตฌ์ฑํ๋ ํ๋์ ๊ตฌ์ฑ์์๋ฅผ ๋งํฌ(Link)๋ผ๊ณ ๋ถ๋ฅด๊ณ , ๋งํฌ์ ๋งํฌ๋ฅผ ์ฐ๊ฒฐํ๋ ์ฐ๊ฒฐ๋ถ๋ฅผ ์กฐ์ธํธ(Joint)๋ผ๊ณ ๋ถ๋ฆ ๋๋ค. ์ฐ๋ฆฌ๋ ๋งํฌ๊ณผ ์กฐ์ธํธ์ ์กฐํฉ์ ํตํด ์ฐ๋ฆฌ๊ฐ ์ํ๋ ํํ์ ๋ก๋ด์ URDF๋ฅผ ํตํด ํํํ ์ ์์ต๋๋ค.
๊ทธ๋ฆฌ๊ณ ์๋์ ๋ด์ฉ์ ํ์ฌ๊น์ง๋ ์ง์ํ์ง ์์ผ๋, URDF๋ก ๋ชจ๋ ๋ก๋ด์ ํํํ ์๋ ์๋ ์ ์ฐธ๊ณ ๋ถํ๋๋ฆฝ๋๋ค.
The main limitation at this point is that only tree structures can be represented, ruling out all parallel robots. Also, the specification assumes the robot consists of rigid links connected by joints; flexible elements are not supported.
Link
๋งํฌ๋ ์์ ์๊ฐํ๋ฏ์ด ๋ก๋ด์ ์ด๋ฃจ๋ ๊ตฌ์ฑ์์ ์ค ํ๋์ด๋ฉฐ, ๋งํฌ๋ ์๋์ ์ธ๊ฐ์ง ์์ฑ์ ์ง๋๋๋ค. ์ธ๊ฐ์ง ์์ฑ ๋ชจ๋ ํ์์ ๋ ฅ ์ต์ ์ ์๋๋ฉฐ, Intertial์ ๊ฒฝ์ฐ default๊ฐ์ผ๋ก 0 mass์ 0 inertia ๋ก ์์ฑ๋ฉ๋๋ค.
- <intertial>: ๋งํฌ์ ๋ํ ๊ด์ฑ ์ ๋ณด๋ค. ๋งํฌ์ ๊ด์ฑ ์ค์ฌ๊ณผ ์ง๋, ๊ด์ฑ๊ณ์ ๋ฑ์ ์ ํ ์ ์๋ค.
- <visual>: ์๊ฐํ ์์ฑ์ผ๋ก, Rviz์ ๊ฐ์ ์๊ฐํ ํด์ ์ฌ์ฉํ ๋ ํจ๊ณผ์ ์ผ๋ก ๊ฐ๋ฐํ ์ ์๋ค.
- <collision>: ๋ฌผ๋ฆฌ์ ์ธ ์ถฉ๋ ์์ฑ์ ์ ํ๋ค. Visual ์์ฑ๊ณผ ๋ค๋ฅด๊ฒ ์ค์ ํ ์ ์๋ค.
Joint
์กฐ์ธํธ๋ ๋งํฌ์ ๋งํฌ๋ฅผ ์ฐ๊ฒฐํ๋ ๋ก๋ด์ ๊ตฌ์ฑ์์์ด๋ฉฐ, URDF ์กฐ์ธํธ๋ 6๊ฐ์ง ํ์ ์ ์ง์ํฉ๋๋ค. ๋ก๋ด์ ์กฐ์ธํธ์ ๋ง๊ฒ ๊ณจ๋ผ ์ฌ์ฉํ๋ฉด ๋ฉ๋๋ค. ์กฐ์ธํธ์ ๊ฒฝ์ฐ์๋ ์ ๋ ฅ ๊ฐ๋ฅํ ์์ฑ๋ค์ด ์์ผ๋ฉฐ, ๋งํฌ์ ๋ฌ๋ฆฌ ์กฐ์ธํธ๋ ํ์์ ๋ ฅ ์์ฑ๋ค๋ ์ง๋๋๋ค.
- <origin>: ๋ถ๋ชจ(parent) ๋งํฌ์์ ์์(child) ๋งํฌ์ ๊ดํ ๋ณํ(transform) ์ ๋ณด
- <parent>: ๋ถ๋ชจ ๋งํฌ ์ด๋ฆ
- <child>: ์์ ๋งํฌ ์ด๋ฆ
๊ทธ ์ธ ์์ฑ๋ค์ ๋ชจ๋ ํ์์ ๋ ฅ ์์ฑ์ ์๋๋ฉฐ, <origin> ๋ํ ๋งํฌ์ ๋ง์ฐฌ๊ฐ์ง๋ก ๊ธฐ๋ณธ ์ ๋ ฅ๊ฐ์ด ์๊ธฐ ๋๋ฌธ์ ์ต์ ์ผ๋ก ์ ๋ ฅ๊ฐ๋ฅํฉ๋๋ค.
3. Link & Joint: URDF & SDF
Link & Joint: URDF
URDF ํ์์ ์ฌ์ฉํ์ฌ ๊ธฐ๋ณธ ๋ชจ๋ฐ์ผ ๋ก๋ด(์ด ํํ ๋ฆฌ์ผ์ ํ์ง ์ด๋ฏธ์ง์ ์๋ ๊ฒ๊ณผ ๊ฐ์)์ ๋ํ ๊ธฐ๋ฐ์ ๋ง๋ญ๋๋ค. base_link ์ขํ๊ณ๋ base_footprint ์ขํ๊ณ ๋ณด๋ค 0.2m ์์ ์์นํ๋ค๊ณ ๊ฐ์ ํฉ๋๋ค . ์ํคํ ์ฒ์ ์ํ ํ๋ก๋๋ ๋ค์๊ณผ ๊ฐ์ต๋๋ค.
๋ค์์ ์ํ URDF ์ฝ๋์ ๋๋ค. base_footprint ๋งํฌ ์ base_link๋ฅผ ์ ์ํฉ๋๋ค .
<?xml version="1.0" ?>
<robot name="my_robot" xmlns:xacro="http://ros.org/wiki/xacro">
<!-- ****************** ROBOT BASE FOOTPRINT *************************** -->
<!-- Define the center of the main robot chassis projected on the ground -->
<link name="base_footprint">
</link>
<!-- ********************** ROBOT BASE ********************************* -->
<link name="base_link">
<visual>
<origin xyz="-0.10 0 0" rpy="${pi/2} 0 ${pi/2}"/>
<geometry>
<mesh filename="file://$(find my_robot)/meshes/my_robot/robot_base.stl" />
</geometry>
<material name="White">
<color rgba="${255/255} ${255/255} ${255/255} 1.0"/>
</material>
</visual>
<collision>
<origin xyz="0 0 -0.15" rpy="0 0 0"/>
<geometry>
<box size="0.70 0.30 0.01"/>
</geometry>
</collision>
</link>
<gazebo reference="base_link">
<material>Gazebo/White</material>
</gazebo>
<!-- The base footprint of the robot is located underneath the chassis -->
<joint name="base_joint" type="fixed">
<parent link="base_footprint"/>
<child link="base_link" />
<origin xyz="0 0 0.2" rpy="0 0 0"/>
</joint>
</robot>
์ URDF ํ์ผ์ joint ์ ์๋ฅผ ๋ณด๋ฉด base_footprint ์ขํ ํ๋ ์ ๋ด๋ถ์ base_link ํฌ์ฆ๊ฐ ๋ค์๊ณผ ๊ฐ์ ๊ฒ์ ์ ์ ์์ต๋๋ค(x=0, y=0, z=0.2, roll = 0 rad, pitch = 0 rad, yaw = 0 rad). ์ด ์ ๋ณด๋ ์กฐ์ธํธ์ <origin></origin> ํ๊ทธ ๋ด์ ํฌํจ๋์ด์ผ ํฉ๋๋ค.
์ฆ, base_link์ base_footprint๋ ์ ํํ ๋์ผํ ๋ฐฉํฅ์ ๊ฐ์ง๋ฉฐ x, y ๋ฐ z ์ถ์ ๋ชจ๋ ๋์ผํ ๋ฐฉํฅ์ ๊ฐ๋ฆฌํต๋๋ค. ๊ทธ๋ฌ๋ base_link๋ ์์ z ๋ฐฉํฅ (์: ์)์ผ๋ก 0.2๋ฏธํฐ์ ์์นํฉ๋๋ค.
์ด์ base_link์ ๋ํ ๋งํฌ ์ ์ ๋ด๋ถ๋ฅผ ์ดํด๋ณด๋ฉด ๋งํฌ์ ์๊ฐ์ ๋ฐ ์ถฉ๋ ์์ฑ์ ์ ์ํ ๊ฒ์ ๋ณผ ์ ์์ต๋๋ค.
- visual ์์ฑ์ ์๋ฎฌ๋ ์ด์ ์์ ๋ก๋ด์ด ์ด๋ป๊ฒ ๋ณด์ด๋์ง ์ ์ํฉ๋๋ค.
- collision ์์ฑ์ Gazebo ์๋ฎฌ๋ ์ด์ ํ๊ฒฝ์์ ๋ก๋ด๊ณผ ๋ค๋ฅธ ๊ฐ์ฒด์ ์ถฉ๋์ ์ ์ดํ๋ โโ๋ฌผ๋ฆฌ์ ์์ฑ์ ์ ์ํฉ๋๋ค.
์ข ์ข ์๊ฐ์ ์์ฑ๊ณผ ์ถฉ๋ ์์ฑ์ด ๋์ผํฉ๋๋ค. ๊ทธ๋ฌ๋ Gazebo์ ๊ฐ์ ์๋ฎฌ๋ ์ด์ ์์ง์ ๋ ๋น ๋ฅด๊ฒ ์คํํ๋ ค๋ฉด ๋ก๋ด์ base_link๋ฅผ ๋ ๋ณต์กํ ๋ชจ์์ด๋ ๋ฉ์ฌ๊ฐ ์๋ cube๋ก ํํํ๋ ๊ฒ์ด ์ข์ต๋๋ค.
Link & Joint: URDF (visual & collision)
์ด ํํ ๋ฆฌ์ผ ์์ ์๊ฐ์ ๋ฐ ์ถฉ๋ ์์ฑ์ ๋ํ ๋ชจ๋ ๋ด์ฉ์ ๋ฐฐ์ธ ์ ์์ต๋๋ค .
์๊ฐ์ ๋ฐ ์ถฉ๋ ์์ฑ์ ๋ณ๋์ <origin></origin> ํ๊ทธ ๋ด์ ์ ์๋ ์์ฒด ํฌ์ฆ๋ฅผ ๊ฐ์ง ์ ์์ต๋๋ค. ์ด๋ฌํ ํ๊ทธ ๋ด๋ถ์ ์ ์๋ ํฌ์ฆ๋ ๋งํฌ์ ํฌ์ฆ๋ฅผ ๊ธฐ์ค์ผ๋ก ํฉ๋๋ค(x=0, y=0, z=0.2, roll = 0 rad, pitch = 0 rad, yaw = 0 rad). visual, collision, and inertial ๋ด <origin></origin> ํ๊ทธ ๋ด๋ถ์ ํฌ์ฆ๋ฅผ ํน์ ๋งํฌ ์ขํ ํ๋ ์์ ์คํ์ ์ผ๋ก ์๊ฐํ ์ ์์ต๋๋ค.
์๋ฅผ ๋ค์ด, collision ํ์์ ๋ค์ ์ดํด๋ณด์ธ์.
<collision>
<origin xyz="0 0 -0.15" rpy="0 0 0"/>
<geometry>
<box size="0.70 0.30 0.01"/>
</geometry>
</collision>
์์ ์ฝ๋๊ฐ ์๋ฏธํ๋ ๋ฐ๋ ๋ก๋ด์ ๊ธฐ๋ณธ ์ถฉ๋ ํ์์ด ๋๊ป๊ฐ 0.1๋ฏธํฐ์ธ ํ๋ธ๋ผ๋ ๊ฒ์ ๋๋ค. ํ๋ธ์ ์ง๋ ์ค์ฌ์ base_link ํฌ์ฆ์์ 0.15m ์๋์ ์์ต๋๋ค. ๊ทธ๋ฆฌ๊ณ base_link๋ base_footprint๋ณด๋ค 0.2m ์์ ์์นํ๋ฏ๋ก ์ถฉ๋ ํ์์ ์ง๋ ์ค์ฌ์ ๊ธฐ๋ณธ ๋ฐ์๊ตญ๋ณด๋ค 0.05m(0.20 – 0.15) ์์ ์์นํฉ๋๋ค.
์๋ ์ด ์น์ ์์ ๋ณผ ์ ์๋ฏ์ด visual geometry์ base_link ์์ ์์ 0.10๋ฏธํฐ ๋ค์ ์์นํฉ๋๋ค. ๋ํ base_link ์ขํ ํ๋ ์์ ๊ธฐ์ค์ผ๋ก x ๋ฐ z ์ถ์ ์ค์ฌ์ผ๋ก 90๋(์: pi/2) ํ์ ํฉ๋๋ค.
<visual>
<origin xyz="-0.10 0 0" rpy="${pi/2} 0 ${pi/2}"/>
<geometry>
<mesh filename="file://$(find my_robot)/meshes/my_robot/robot_base.stl" />
</geometry>
<material name="White">
<color rgba="${255/255} ${255/255} ${255/255} 1.0"/>
</material>
</visual>
์์ฝํ์๋ฉด, URDF ํ์ผ์์ ์ขํ๊ณ๋ฅผ ์ ์ํ๊ธฐ ์ํ ์ฃผ์ ์์ ์ <joint>…<origin></origin></joint> ํ๊ทธ์ ๋๋ค. ๋งํฌ ์ ์ ๋ด์ <origin></origin> ํญ์ visual, collision, and inertial ํ์์ ์ฝ๊ฐ ์กฐ์ /์คํ์ ํ๋ ๋ฐ์๋ง ์ฌ์ฉ ๋ฉ๋๋ค .
Link & Joint: SDF
์ด์ SDF ํ์์ผ๋ก ์ ์๋ ๋์ผํ ๋ก๋ด ๋ฒ ์ด์ค๋ฅผ ์ดํด๋ณด๊ฒ ์ต๋๋ค. ์ฝ๋๋ ๋ค์๊ณผ ๊ฐ์ต๋๋ค.
<?xml version="1.0" ?>
<sdf version="1.6">
<model name="my_robot">
<static>false</static>
<!-- ****************** ROBOT BASE FOOTPRINT *************************** -->
<link name="base_footprint"/>
<!-- ********************** ROBOT BASE ********************************* -->
<link name="base_link">
<!-- The pose below is always the global pose with respect to the
origin (i.e. base_footprint) of the robot model -->
<pose>0 0 0.2 0 0 0</pose>
<collision name="base_link_collision">
<!-- The pose below is the local pose with respect to this link -->
<pose>0 0 -0.15 0 0 0</pose>
<geometry>
<box>
<size>0.7 0.3 0.1</size>
</box>
</geometry>
</collision>
<visual name="base_link_visual">
<pose>-0.10 0 0 1.5708 0 1.5708</pose>
<geometry>
<mesh>
<uri>model://my_robot/meshes/robot_base.stl</uri>
<scale>1.0 1.0 1.0</scale>
</mesh>
</geometry>
<material>
<ambient>1.0 1.0 1.0 1.0</ambient>
<diffuse>1.0 1.0 1.0 1.0</diffuse>
<specular>0.0 0.0 0.0 1.0</specular>
<emissive>0.0 0.0 0.0 1.0</emissive>
</material>
</visual>
</link>
<!-- ************************ JOINTS *********************************** -->
<!-- Pose of the joint is the same as the child link frame -->
<joint name="base_joint" type="fixed">
<parent>base_footprint</parent>
<child>base_link</child>
<pose>0 0 0 0 0 0</pose>
</joint>
</model>
</sdf>
base_link์ ํฌ์ฆ๊ฐ <link> <pose></pose> …</link> ํ๊ทธ ๋ฐ๋ก ๋ด๋ถ์ ์ค์ ๋์ด ์๋ ๊ฒ์ ๋ณผ ์ ์์ต๋๋ค. ๋ก๋ด ๋ด๋ถ์ ๋งํฌ๊ฐ ๋ฌด์์ด๋ ๊ด๊ณ์์ด ์ด ํฌ์ฆ๋ ๋ชจ๋ธ์ ์์ (์: ๋ชจ๋ฐ์ผ ๋ก๋ด์ ๊ฒฝ์ฐ base_footprint )์ ๊ธฐ์ค์ผ๋ก ํญ์ ์ ์ญ ํฌ์ฆ์ ๋๋ค.
์ถฉ๋ ๋ฐ ์๊ฐ์ ๊ธฐํํ ํ๊ทธ ๋ด๋ถ์ ํฌ์ฆ๋ URDF ํ์ผ์ ์ถฉ๋ ๋ฐ ์๊ฐ์ ๊ธฐํํ ์ ์ ๋ด๋ถ์ <origin></origin> ํ๊ทธ์ ์ ํํ ๋์ผํ๊ฒ ์๋ํฉ๋๋ค. ์ด๋ฌํ ํฌ์ฆ๋ ํด๋น ํน์ ๋งํฌ์ ํฌ์ฆ์ ๋ํ ์คํ์ ์ ๋๋ค.
ํ์ ๋งํฌ์ ํฌ์ฆ์์ ์คํ์ ๋ <joint></joint> ํ๊ทธ ๋ด๋ถ์ ํฌ์ฆ์ ๋๋ค . ํ์ ๋งํฌ์ ํฌ์ฆ๋ ์๋์ ๊ฐ์ด ๋งํฌ ์ ์ ๋ด๋ถ(์: ์ด๊ธฐ <pose></pose> ํ๊ทธ ๋ด๋ถ)์ ์ค์ ๋๋ฏ๋ก ๋ก๋ด ๋ชจ๋ธ์ ๋ชจ๋ ๊ด์ ์ ๋ํด ๊ฑฐ์ ํญ์ ์ด ๊ฐ์ ๋ชจ๋ 0์ผ๋ก ์ค์ ํฉ๋๋ค.
<link name="base_link">
<!-- The pose below is always the global pose with respect to the
origin (i.e. base_footprint) of the robot model -->
<pose>0 0 0.2 0 0 0</pose>
๋ฐ๋ผ์ ์์ฝํ๋ฉด SDF ํ์ผ์์ ์ขํ ํ๋ ์์ ์ ์ํ๊ธฐ ์ํ ์ฃผ์ ์์ ์ <joint> …<origin></origin></joint> ์ด ์๋ <link><pose></pose>…</link> ํ๊ทธ์ ๋๋ค. SDF ํ์ผ์ ๋งํฌ๋ณ ์๊ฐ์ , ์ถฉ๋ ๋ฐ ๊ด์ฑ ํฌ์ฆ ์กฐ์ ์ <origin></origin> ํ๊ทธ ๊ฐ ์๋ <pose></pose> ํ๊ทธ ๋ด๋ถ์์ ์ ์๋ฉ๋๋ค.
๋์ผ๋ก..
๋งํฌ์ ์กฐ์ธํธ ์กฐํฉ์ผ๋ก ํ์ํ ๋ก๋ด๊ตฌ์ฑ์ ์์ฑํ๋ฉด ๋ฉ๋๋ค. ์ตํ ์๋ ค์ง ํํ์ ๋ก๋ด์ ๋๋ถ๋ถ ์ฐธ์กฐํ ๋งํ ํ๋ก์ ํธ๋ค์ด ์์ผ๋ ์ฐธ๊ณ ํ๋๋ก ํฉ์๋ค.
์ฐธ๊ณ
- http://wiki.ros.org/urdf
- http://wiki.ros.org/tf/Tutorials
- http://wiki.ros.org/urdf/XML/model
- http://wiki.ros.org/urdf/XML/link
- http://wiki.ros.org/urdf/XML/joint
- [Blog] URDF vs. SDF – Link Pose, Joint Pose, Visual & Collision: https://automaticaddison.com/urdf-vs-sdf-link-pose-joint-pose-visual-collision/
- [Blog] ROS URDF ์์ฑํ๊ธฐ: https://medium.com/newworld-kim/ros-urdf-b6979bfa31aa
'Study: Robotics(Robot) > Robot: ROS(Robot Operating Sytem)' ์นดํ ๊ณ ๋ฆฌ์ ๋ค๋ฅธ ๊ธ
[ROS] gazebo clearpath jackal ๋ชจ๋ฐ์ผ ๋ก๋ด ์ฌ์ฉํ๊ธฐ(velodyne vlp16 3d lidar) (0) | 2023.11.13 |
---|---|
[ROS] apt ์ค์นํ ํจํค์ง์ buildํ ํจํค์ง(catkin, colcon) ์ค ์ด๋ค ๊ฒ์ ์ฌ์ฉ? (0) | 2023.11.10 |
[ROS] ROS TF ์ขํ๊ณ ๋ฐ ๋ณํ (0) | 2023.10.26 |
[ROS] ROS rosrun ์คํํ์ผ ๋ง๋ค๊ธฐ(python, cpp) (0) | 2023.10.12 |
[ROS] ROS Docker Official Image, Docker Compose ํ์ผ (0) | 2023.05.03 |