로봇 모델 시각화
Moby Description 패키지
moby_description
패키지는 RViz 및 Gazebo 시뮬레이터에서 사용할 모델 파일(URDF)을 포함하고 있습니다.
로봇 모델
- URDF (The Universal Robotic Description Format): 로봇의 기구학 및 동역학적 요소를 기술하는 XML 형식 파일입니다.
- Xacro: XML + Macro의 합성어로 로봇모델을 간단하게 메크로를 사용하여 XML 파일을 생성 할 수 있게 해줍니다.
moby_description
패키지의 urdf 폴더에는, Moby 모델(MobyRP, MobyRP_V3)의 모든 구성을 포함하는 config
폴더가 있습니다. 다른 xacro 파일은 config
폴더의 파일을 읽고 로봇을 구성합니다.
아래 다이어그램은 파일 간의 관계를 보여줍니다.
joint_limits ────────┐
kinematics ──────────┤
physical_parameters ─┤
visual_parameters ───┤
moby_common ─┤
moby_transmission ─┤
materials ─┴─ moby_macro─moby.urdf
urdf 및 xacro에 대한 자세한 정보는 아래 링크를 참고하십시오. ROS1 build model tutorial
Rviz 실행
Moby 모델은 RViz를 통해 시각화 될 수 있습니다. launch 파일은 한 번에 여러 ROS 노드를 시작하는 파일입니다. 다음 명령어를 통해 ROS에서 robot description을 실행하고 로봇 모델을 시각화 할 수 있습니다.
moby_type
을 "moby_rp"로 지정하면, launch 파일이 적절한 구성 파일을 로드하고 RViz와 같은 시각화 도구에 로봇을 표시하는 데 필요한 노드를 실행합니다.
실행 후 Rviz 화면을 확인할 수 있습니다.
joint_states_publisher
의 joint position 값을 수정하는 것으로, RViz에서 Indy의 관절과 Moby 바퀴의 위치를 변경할 수 있습니다.
Launch 파일
아래의 코드는 위의 명령에서의 moby_description.launch입니다.
<?xml version="1.0"?>
<launch>
<arg name="prefix" default=""/>
<arg name="name" default="moby"/>
<arg name="moby_type" default=""/>
<arg name="rviz" default="true"/>
<arg name="sim_gazebo" default="false"/> <!--is sim gazebo?-->
<arg name="joint_state" default="true"/> <!--need joint state? -->
<param name="robot_description" command="$(find xacro)/xacro --inorder '$(find moby_description)/urdf/moby.urdf.xacro'
prefix:=$(arg prefix)
name:=$(arg name)
moby_type:=$(arg moby_type)
sim_gazebo:=$(arg sim_gazebo)"/>
<!--joint state-->
<group if="$(eval arg('rviz') == true and arg('sim_gazebo') == false and arg('joint_state') == true)">
<node name="joint_state_publisher_gui" pkg="joint_state_publisher_gui" type="joint_state_publisher_gui"/>
</group>
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher"/>
<!--rviz-->
<node if="$(arg rviz)" pkg="rviz" type="rviz" name="rviz" args="-d $(find moby_description)/rviz_config/moby.rviz"/>
</launch>
-
robot_description:
moby.urdf.xacro
를 읽고,joint_state_publisher
노드에 관련된 파라미터입니다. -
joint_state_publisher:
robot_description
의 관절 및 바퀴 위치를 /joint_states 토픽으로 발행합니다. -
robot_state_publisher: /joint_states 토픽을 구독하고 각 링크의 transform을 발행합니다.
-
rviz : RViz 노드를 실행하고, rviz 설정 파일 (moby_description/rviz_config/moby.rviz)을 로드합니다.
robot_state_publisher
노드에서 발행된tf
를 구독하고 시각화합니다.