Skip to content

로봇 모델 시각화

Indy Description 패키지

indy_description 패키지는 RVizGazebo 시뮬레이터에서 사용할 모델 파일(URDF)을 포함하고 있습니다.

├── indy_description
    ├── urdf
    ├── launch
    ├── rviz_config
    ├── meshes
    └──  ...

로봇 모델

  • URDF (The Universal Robotic Description Format): 로봇의 기구학 및 동역학적 요소를 기술하는 XML 형식 파일입니다.
  • Xacro: XML + Macro의 합성어로 로봇모델을 간단하게 메크로를 사용하여 XML 파일을 생성 할 수 있게 해줍니다.

indy_description 패키지의 urdf 폴더에는 Indy 모델(Indy7, Indy7v2, Indy12, Indy12v2, IndyRP, IndyRPv2)의 모든 구성을 포함하는 config 폴더가 있습니다. 다른 xacro 파일은 config 폴더의 파일을 읽고 로봇을 구성합니다.

아래 다이어그램은 파일 간의 관계를 보여줍니다.

joint_limits ────────┐
kinematics ──────────┤
physical_parameters ─┤
visual_parameters ───┴─ indy_common ─┐
                  indy_transmission ─┤
                          materials ─┴─ indy_macro─indy.urdf

urdf와 xacro에 대한 자세한 정보는 ROS 모델 빌드 튜토리얼을 참조하십시오.

RViz 실행

Indy 모델은 RViz를 통해 시각화할 수 있습니다. launch 파일은 여러 ROS 노드를 동시에 실행하기 위한 파일입니다. 다음 명령어를 통해 ROS에서 Indy7 로봇 모델을 시각화 할 수 있습니다.

$ roslaunch indy_description indy_description.launch indy_type:=indy7

indy_type을 "indy7"로 지정하면, launch 파일이 적절한 구성 파일을 로드하고 RViz와 같은 시각화 도구에 로봇을 표시하는 데 필요한 노드를 실행합니다.

아래와 같이 창이 실행된 것을 볼 수 있습니다.


아래와 같이 indy_eye 옵션을 true로 하게될 경우 IndyEye 모델 로봇을 시각화 할 수 있습니다.

$ roslaunch indy_description indy_description.launch indy_type:=indy7 indy_eye:=true


joint_states_publisher의 관절 위치 값을 조정하여 RViz에서 로봇의 위치를 변경할 수 있습니다.

Launch 파일

아래 코드는 위 명령어에서 사용하는 indy_description.launch입니다.

<?xml version="1.0"?>
<launch>
  <arg name="prefix"        default=""/>
  <arg name="name"      default="indy"/>
  <arg name="indy_type"     default="indy7"/>
  <arg name="indy_eye"  default="false"/>
  <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  indy_description)/urdf/indy.urdf.xacro'
    prefix:=$(arg prefix)
    name:=$(arg name)
    indy_type:=$(arg indy_type)
    indy_eye:=$(arg indy_eye)
    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 indy_description)/rviz_config/indy.rviz"/>

</launch>
  • robot_description: indy.urdf.xacro를 읽고, joint_state_publisher 노드의 파라미터로 사용됩니다.

  • joint_state_publisher: /joint_states 토픽을 사용하여 robot_description의 관절 위치를 퍼블리시합니다.

  • robot_state_publisher: /joint_states 토픽을 구독하고 각 링크의 변환(transform)을 퍼블리시합니다.

  • rviz : rviz 구성 파일(indy_description/rviz_config/indy.rviz)을 로드하여 RViz 노드를 실행합니다. robot_state_publisher 노드에서 게시한 tf를 구독하고 이를 시각화합니다.