Mobile 로봇 Simulation

Gazebo Mobile 로봇 모델 만들기

Mobile 로봇에 3D 센서 모델과 2D 레이저 모델 추가하기

토픽 결과물: Mobile 로봇 모델에, 3D 센서와 Laser 센서가 추가됩니다.

이번 토픽은 Gazebo를 이용하여 Mobile 로봇을 만드는 것에 대한 것입니다. 로봇 모델은 3D센서로서 Turtlebot with ASUS Xtion Pro를 사용하고, 추가적으로 Hokuyo 2D Laser Scanner가 부착된 형태입니다. Hokuyo 센서를 부착하는 방법은 이 사이트를 참고하면 됩니다.

설명 동영상

URDF 모델 생성

ROS Indigo에서 제공하는 Turtlebot (Kobuki)의 urdf 파일을 사용하고, Hokuyo laser scanner urdf 파일을 생성합니다. 먼저, Turtlebot 관련 패키지를 아래와 같이 모두 설치합니다.

$ sudo apt-get install ros-indigo-turtlebot-*

그런 다음, 아래와 같이 Turtlebot 관련 urdf 파일 (common_properties.urdf.xacro, turtlebot_gazebo.urdf.xacro, turtlebot_library.urdf.xacro, turtlebot_properties.urdf.xacro)을 복사하여 mobile_robot_sim 패키지에 복사합니다.

$ roscd mobile_robot_sim
$ mkdir urdf
$ roscd turtlebot_description/urdf
$ cp *.xacro ~/catkin_ws/src/mobile_robot_sim/urdf

turtlebot_library.urdf.xacro파일을 보면 turtlebot을 구성하는 urdf 파일들이 나타나는데, 이번 토픽에서 사용되는 로봇에 구성은 다음과 같습니다.

  • 로봇 베이스: kobuki
  • Stack: hexagons (로봇 베이스 위에 쌓는 Stack의 형태)
  • 3D 센서: ASUS Xtion Pro (Kinect보다 좋다?)
  • 2D 센서: hokuyo 2d laser

Turtlebot with Hokuyo Laser 모델 

위 그림에서 기존 Turtlebot과 달리, Kinect가 ASUS Xtion으로 변경되었고, stack 첫번째 단의 회색 부분의 Hokuyo 센서가 부착되었습니다. 이와 같은 모델을 만들기 위해서 먼저 /opt/ros/indigo/share/turtlebot_description/urdf 밑에서 아래 파일들을 mobile_robot_sim 패키지의 urdf 디렉터리로 복사합니다. kobuki.urdf.xacro 파일은 /opt/ros/indigo/share/kobuki_description/urdf/kobuki.urdf.xacro 에 있습니다.

hexagons.urdf.xacro
asus_xtion_pro.urdf.xacro
kobuki.urdf.xacro

hokuyo urdf 파일은 존재하지 않기 때문에, 아래와 같이 mobile_robot_sim 패키지의 urdf 디렉터리에 생성합니다. 파일이름은 hokuyo.urdf.xacro로 합니다.

<?xml version="1.0"?>
<robot name="sensor_hokuyo" xmlns:xacro="http://ros.org/wiki/xacro">
  <xacro:include filename="$(find mobile_robot_sim)/urdf/turtlebot_gazebo.urdf.xacro"/>
  <xacro:include filename="$(find mobile_robot_sim)/urdf/turtlebot_properties.urdf.xacro"/>
  <!-- Hokuyo 2D LIDAR -->
  <xacro:macro name="sensor_hokuyo" params="parent">
    <joint name="laser" type="fixed">
      <origin xyz="0.10 0.0 0.17" rpy="3.14159 0.0 0.0" />
      <parent link="base_link" />
      <child link="base_laser_link" />
    </joint>

    <link name="base_laser_link">
      <visual>
        <geometry>
          <box size="0.00 0.03 0.03" />
        </geometry>
        <material name="Green" />
      </visual>
      <inertial>
        <mass value="0.000001" />
        <origin xyz="0 0 0" />
        <inertia ixx="0.0001" ixy="0.0" ixz="0.0"
          iyy="0.0001" iyz="0.0"
          izz="0.0001" />
      </inertial>
    </link>
    <!-- Set up laser gazebo details -->
    <hokuyo_laser />
  </xacro:macro>
</robot>

여기서 아래 부분을 보면 방금전 turtlebot_description에서 복사한 파일을 인클루드 하고 있습니다.

<xacro:include filename="$(find mobile_robot_sim)/urdf/turtlebot_gazebo.urdf.xacro"/>
<xacro:include filename="$(find mobile_robot_sim)/urdf/turtlebot_properties.urdf.xacro"/>

그리고 센서의 위치를 태그에 넣어줍니다. 여기서는 <origin xyz="0.10 0.0 0.17" rpy="3.14159 0.0 0.0" />로 설정하였습니다.

그 다음으로 위에서 생성한 hokuyo.urdf.xacro를 turtlebot_library.urdf.xacro에 추가합니다. turtlebot_library.urdf.xacro 파일 내용은 아래와 같습니다. 원래 파일에서 로봇에서 필요한 부분만 남기고 나머지는 삭제하였습니다.

<?xml version="1.0"?>
<!--
  The complete turtlebot library of xacros for easy reference
 -->
<robot xmlns:xacro="http://ros.org/wiki/xacro">
  <!-- General -->
  <xacro:include filename="$(find mobile_robot_sim)/urdf/common_properties.urdf.xacro"/>
  <xacro:include filename="$(find mobile_robot_sim)/urdf/turtlebot_properties.urdf.xacro"/>
  <!-- Bases -->
  <xacro:include filename="$(find mobile_robot_sim)/urdf/kobuki.urdf.xacro" />
  <!-- Stacks -->
  <xacro:include filename="$(find mobile_robot_sim)/urdf/hexagons.urdf.xacro"/>
  <!-- 3D Sensors -->
  <xacro:include filename="$(find mobile_robot_sim)/urdf/asus_xtion_pro.urdf.xacro"/>
  <!-- 2D Hokuyo Laser -->
  <xacro:include filename="$(find mobile_robot_sim)/urdf/hokuyo.urdf.xacro"/>
</robot>

다음으로, turtlebot_description/urdf/robots/kobuki_hexagons_asus_xtion_pro.urdf.xacro 파일과 유사하게 hokuyo 센서가 추가된 urdf파일을 아래과 같이 mobile_robot_sim의 urdf 디렉터리에 kobuki_hexagons_asus_hokuyo.urdf.xacro랴는 이름으로 생성합니다.

<?xml version="1.0"?>
<!--
    - Base      : kobuki
    - Stacks    : hexagons
    - 3d Sensor : asus
    - 2d Laser  : hokuyo
-->    
<robot name="turtlebot" xmlns:xacro="http://ros.org/wiki/xacro">

  <xacro:include filename="$(find mobile_robot_sim)/urdf/turtlebot_library.urdf.xacro" />
  
  <kobuki/>
  <stack_hexagons                 parent="base_link"/>
  <sensor_asus_xtion_pro          parent="base_link"/>
  <sensor_hokuyo                  parent="base_link"/>
</robot>

위 파일에서 <sensor_hokuyo parent="base_link"/>가 추가된 부분이며, sensor_hokuyo라는 것을 hokuyo.urdf.xacro의 robot tag 이름과 같아야 합니다. 여기까지 하면 hokuyo 센서가 추가된 turtlebot (kobuki)의 urdf 모델 생성이 완료됩니다.

Gazebo 설정

위에서 생성한 urdf를 gazebo에서 사용하기 위해서는 아래의 작업들이 필요합니다.

  • turtlebot_gazebo.urdf.xacro 수정 먼저, turtlebot_gazebo.urdf.xacro 파일에 아래와 같이 hokuyo sensor 부분을 추가합니다.
<?xml version="1.0"?>
<robot name="turtlebot_gazebo" xmlns:xacro="http://ros.org/wiki/xacro">
  <!-- Microsoft Kinect / ASUS Xtion PRO Live for simulation -->
  <xacro:macro name="turtlebot_sim_3dsensor">
    <gazebo reference="camera_link">  
      <sensor type="depth" name="camera">
        <always_on>true</always_on>
        <update_rate>20.0</update_rate>
        <camera>
          <horizontal_fov>${60.0*M_PI/180.0}</horizontal_fov>
          <image>
            <format>R8G8B8</format>
            <width>640</width>
            <height>480</height>
          </image>
          <clip>
            <near>0.05</near>
            <far>8.0</far>
          </clip>
        </camera>
        <plugin name="kinect_camera_controller" filename="libgazebo_ros_openni_kinect.so">
          <cameraName>camera</cameraName>
          <alwaysOn>true</alwaysOn>
          <updateRate>10</updateRate>
          <imageTopicName>rgb/image_raw</imageTopicName>
          <depthImageTopicName>depth/image_raw</depthImageTopicName>
          <pointCloudTopicName>depth/points</pointCloudTopicName>
          <cameraInfoTopicName>rgb/camera_info</cameraInfoTopicName>
          <depthImageCameraInfoTopicName>depth/camera_info</depthImageCameraInfoTopicName>
          <frameName>camera_depth_optical_frame</frameName>
          <baseline>0.1</baseline>
          <distortion_k1>0.0</distortion_k1>
          <distortion_k2>0.0</distortion_k2>
          <distortion_k3>0.0</distortion_k3>
          <distortion_t1>0.0</distortion_t1>
          <distortion_t2>0.0</distortion_t2>
          <pointCloudCutoff>0.4</pointCloudCutoff>
        </plugin>
      </sensor>
    </gazebo>
  </xacro:macro>
  
  <!-- Hokuyo LIDAR for simulation -->
  <xacro:macro name="hokuyo_laser">
    <gazebo reference="base_laser_link">
      <sensor type="ray" name="laser">
        <pose>0 0 0 0 0 0</pose>
        <visualize>false</visualize>
        <update_rate>30</update_rate>
        <ray>
          <scan>
            <horizontal>
              <samples>720</samples>
              <resolution>1</resolution>
              <min_angle>-1.570796</min_angle>
              <max_angle>1.570796</max_angle>
            </horizontal>
          </scan>
          <range>
            <min>0.01</min>
            <max>5.0</max>
            <resolution>0.01</resolution>
          </range>
          <noise>
            <type>Gaussian</type>
            <mean>0.0</mean>
            <stddev>0.01</stddev>
          </noise>
        </ray>
        <plugin name="hokuyo_node" filename="libgazebo_ros_laser.so">
          <topicName>/hokuyo_scan</topicName>
          <frameName>base_laser_link</frameName>
        </plugin>
      </sensor>
    </gazebo>
  </xacro:macro>
</robot>

위 코드에서 아래 부분이 새롭게 추가된 것이며, 2d 센서의 거리 측정 범위를 태그에 설정하면 됩니다. 여기서는 최소 0.01m에 최대 5m로 하였습니다. 주의깊게 볼 부분은 hokuyo 센서의 scan topic 이름과 frame 이름이 <topicName>/hokuyo_scan</topicName> <frameName>base_laser_link</frameName> 에 각각 설정되어 있습니다. scan topic 수신시에 필요한 부분입니다. Gazebo에서 Laser rays를 출력하고 싶다면 <visualize> 태크값을 true로 하면 아래와 같이 laser rays를 Gazebo에 표시할 수 있습니다.

Hokuyo 센서 Rays 


  • kobuki_hokuyo.launch.xml 파일 생성

Gazebo에서 turtlebot simulation launch 파일 (/opt/ros/indigo/share/turtlebot_gazebo/launch/turtlebot_world.launch)을 보면 아래와 같은 코드가 있습니다.

<include file="$(find turtlebot_gazebo)/launch/includes/$(arg base).launch.xml">
  <arg name="base" value="$(arg base)"/>
  <arg name="stacks" value="$(arg stacks)"/>
  <arg name="3d_sensor" value="$(arg 3d_sensor)"/>
</include>

이 코드는 kobuki.launch.xml을 인클루드 하게 되어 있는데, 이것은 hokuyo 센서가 없기 때문에 아래와 같이 새롭게 만듭니다.

$ roscd mobile_robot_sim
$ mkdir -p launch/includes
$ cd launch/includes
$ touch kobuki_hokuyo.launch.xml

kobuki_hokuyo.launch.xml에는 다음과 같이 작성합니다.

<launch>
  <arg name="base"/>
  <arg name="stacks"/>
  <arg name="3d_sensor"/>
  <arg name="2d_laser"/>
  <arg name="x" default="0.0" />
	<arg name="y" default="0.0" />
  <arg name="theta" default="0.0" />
  <arg name="urdf_file" default="$(find xacro)/xacro.py '$(find mobile_robot_sim)/urdf/$(arg base)_$(arg stacks)_$(arg 3d_sensor)_$(arg 2d_laser).urdf.xacro'" />
  <param name="robot_description" command="$(arg urdf_file)" />
 
  <!-- Gazebo model spawner -->
  <node name="spawn_turtlebot_model" pkg="gazebo_ros" type="spawn_model"
        args="$(optenv ROBOT_INITIAL_POSE) -unpause -urdf -param robot_description -model mobile_base -x $(arg x) -y $(arg y) -Y $(arg theta)" />  
  
  <!-- Velocity muxer -->
  <node pkg="nodelet" type="nodelet" name="mobile_base_nodelet_manager" args="manager"/>
  <node pkg="nodelet" type="nodelet" name="cmd_vel_mux"
        args="load yocs_cmd_vel_mux/CmdVelMuxNodelet mobile_base_nodelet_manager">
    <param name="yaml_cfg_file" value="$(find turtlebot_bringup)/param/mux.yaml" />
    <remap from="cmd_vel_mux/output" to="mobile_base/commands/velocity"/>
  </node>

  <!-- Bumper/cliff to pointcloud (not working, as it needs sensors/core messages) -->
  <include file="$(find turtlebot_bringup)/launch/includes/kobuki/bumper2pc.launch.xml"/>
</launch>

원래의 kobuki.launch.xml 파일에 2d sensor 부분을 추가한 것이며, args="$(optenv ROBOT_INITIAL_POSE) -unpause -urdf -param robot_description -model mobile_base -x $(arg x) -y $(arg y) -Y $(arg theta)" /> 부분에 보이듯이 로봇의 초기위치를 환경변수가 아니라 인자로 넣을 수 있게 하였습니다.


  • Gazebo 실행 launch 파일 생성

원래 turtlebot_gazebo 있는 launch 파일 (/opt/ros/indigo/share/turtlebot_gazebo/launch/turtlebot_world.launch)을 수정하여 위에서 생성한 로봇 모델을 Gazebo에서 불러 들이도록 합니다. 다음과 같이 새롭게 launch 파일을 생성합니다.

$ roscd mobile_robot_sim
$ touch launch/turtlebot_hokuyo.launch

turtlebot_hokuyo.launch에 아래와 같이 작성합니다.

<!-- 
  gazebo mobile robot simulation: kobuki, asus, hokuyo 2d laser
-->
<launch>

  <!-- gazebo initial pose -->
  <arg name="init_x" default="-2.0" />  <!-- -2.0 -->
  <arg name="init_y" default="-2.7" />  <!-- -2.7 -->
  <arg name="init_theta" default="0.0" /> <!-- 0.0 -->
  
  <!-- gazebo setting for turtlbot -->
  <arg name="base"        default="kobuki"/> <!-- create, roomba -->
  <arg name="battery"     default="$(optenv TURTLEBOT_BATTERY /proc/acpi/battery/BAT0)"/>  <!-- /proc/acpi/battery/BAT0 --> 
  <arg name="stacks"      default="hexagons"/>  <!-- circles, hexagons --> 
  <arg name="3d_sensor"   value="asus"/>  <!-- asus_xtion_pro --> 
  <arg name="2d_laser"    value="hokuyo"/> <!-- hokuyo 2d laser -->
  <arg name="world_file"  value="$(find mobile_robot_sim)/worlds/sim_simple.world"/>  

  <!-- include gazebo world -->

  <include file="$(find gazebo_ros)/launch/empty_world.launch">
    <arg name="use_sim_time" value="true"/>
    <arg name="debug" value="false"/>
    <arg name="world_name" value="$(arg world_file)"/>
  </include>

 
  <include file="$(find mobile_robot_sim)/launch/includes/$(arg base)_hokuyo.launch.xml">
    <arg name="base" value="$(arg base)"/>
    <arg name="stacks" value="$(arg stacks)"/>
    <arg name="3d_sensor" value="$(arg 3d_sensor)"/>
    <arg name="2d_laser" value="$(arg 2d_laser)"/>
    <arg name="x" value="$(arg init_x)"/>
    <arg name="y" value="$(arg init_y)"/>
    <arg name="theta" value="$(arg init_theta)"/> 
  </include>

  <node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher">
    <param name="publish_frequency" type="double" value="30.0" />
  </node>

</launch>

이번 토픽에서는 Hokuyo 2D Laser scanner를 사용할 것이기 때문에 기존 turtlebot_world.launch에 있는 Fake laser 부분을 삭제하였습니다. 위 코드를 보면 로봇의 초기위치를 아래와 같이 설정하였습니다. 초기 위치는 토픽2에서 생성한 world 모델에서 로봇이 위치해야 할 곳을 설정합니다.

  <!-- gazebo initial pose -->
  <arg name="init_x" default="-2.0" />  <!-- -2.0 -->
  <arg name="init_y" default="-2.7" />  <!-- -2.7 -->
  <arg name="init_theta" default="0.0" /> <!-- 0.0 -->

초기값은 <include file="$(find mobile_robot_sim)/launch/includes/$(arg base)_hokuyo.launch.xml">의 인자로 쓰입니다. Gazebo world 파일 설정은 아래와 같이 강좌2에서 생성한 mobile_robot_sim/worlds의 sim_simple.world로 하였습니다.

<arg name="world_file"  value="$(find mobile_robot_sim)/worlds/sim_simple.world"/>  
<include file="$(find gazebo_ros)/launch/empty_world.launch">
  <arg name="use_sim_time" value="true"/>
  <arg name="debug" value="false"/>
  <arg name="world_name" value="$(arg world_file)"/>
</include>

  • Gazebo 실행 아래와 같이 위에서 생성한 launch 파일을 실행하면 Gazebo가 실행되며 world 모델과 로봇 모델이 로드됩니다.
$ roslaunch mobile_robot_sim turtlebot_hokuyo.launch

로봇이 world 밖에 있거나 원하는 위치에 있지 않다면, turtlebot_hokuyo.launch에서 init_x, init_y, init_theta를 수정하면 됩니다.

댓글

댓글 본문
버전 관리
이타인
현재 버전
선택 버전
graphittie 자세히 보기