[置顶] ros中利用gazebo进行gmapping仿真:kobuki+kinct -> kobuki+rplidar

         2D SLAM : gmapping

1. 准备的源码。

   可以建一个新的ros工作空间 gampping_ws,在github下面下载好相应的源码。注意更新下gazebo下的model,不然要在线下载(需要goole),所以

给你个离线的包: 链接: http://pan.baidu.com/s/1bnE0mOR 密码: 9mft     (gazebo_models.zip)

将其下载好解压替换你安装的gazebo下的models。 在你home ~ 路径下。显示隐藏文件(ctrl + H ),找到~/.gazebo/models   

mkdir -p ~/gmapping_ws/src
cd ~/gmapping/src
git clonehttps://github.com/robopeak/rplidar_ros.git
git clonehttps://github.com/turtlebot/turtlebot_simulator.git
git clonehttps://github.com/turtlebot/turtlebot_apps.git
git clone https://github.com/turtlebot/turtlebot.git

2. 源码进行相应的gazebo + gampping    (利用kinect三维点云模拟2D laser)

 先启动gazeb, 相当于硬件启动,传感器都启动起来了。 /scan   /dom 有数据了。

启动gmapping , 利用采集到的传感器数据进行制图。   /map 有数据

运行rviz 显示相应的制图信息。

最后运行键盘控制机器人运动制图。   

roslaunch turtlebot_gazebo turtlebot_world.launch
roslaunch turtlebot_gazebo gmapping_demo.launch 
roslaunch turtlebot_rviz_launchers view_navigation.launch 
roslaunch turtlebot_teleop keyboard_teleop.launch 
下图是实际运行的效果图:
[置顶] ros中利用gazebo进行gmapping仿真:kobuki+kinct -> kobuki+rplidar_第1张图片 [置顶] ros中利用gazebo进行gmapping仿真:kobuki+kinct -> kobuki+rplidar_第2张图片

3. 替换传感器接口  (kinct -> rplidar )

  分析: 仿真也就是利用仿真环境下与仿真环境下的传感器感受虚拟的世界,将其感受到的信息发布出来。。(底层采集: 具有依赖性  )

      上层算法制图依赖底层的数据接口。(满足相应的数据接口就可以使用。fake相应的sensor data 也可以,堆底层具体依赖不强)

==》 仿真更换传感器就需要更改模型urdf文件,同时在gazebo里面加入相应的传感器插件去感受相应的仿真环境,并以topic的形式发布出来。

      从上面的分析加上上面源码launch文件看===》只需关注  turtlebot_world.launch  文件就可以。

 3.1. 看 roslaunchturtlebot_gazebo turtlebot_world.launch  文件。

           与传感器模型相关的 语句是: base --- 3d_sensor ===》要换成rplidar

                  <includefile="$(find turtlebot_gazebo)/launch/includes/$(argbase).launch.xml">

 3.2.  看kobuki.launch.xml 文件。= > 关注urdf 文件 ==> 路径在/turtlebot/turtlebot_description/robots 

        <argname="urdf_file" default="$(find xacro)/xacro.py'$(find turtlebot_description)/robots/$(arg base)_$(arg stacks)_$(arg3d_sensor).urdf.xacro'" />


 3.3. 在/turtlebot/turtlebot_description/robots下建立相应的urdf文件  

        仿照kobuki_hexagons_kinect.urdf.xacro文件建立

kobuki_nostack_rplidar.urdf.xacro

kobuki_hexagons_rplidar.urdf.xacro


<sensor_rplidar parent="base_link"/>

<xacro:includefilename="$(findturtlebot_description)/urdf/turtlebot_library.urdf.xacro" />



3.4.  进入文件$(findturtlebot_description)/urdf/turtlebot_library.urdf.xacro添加rplidarurdf文件

<xacro:includefilename="$(findturtlebot_description)/urdf/sensors/rplidar.urdf.xacro"/>

3.5.  在路径$(findturtlebot_description)/urdf/sensors/下建立rplidar.urdf.xacro urdf文件

配置位置信息。laser相对robot的位置 坐标系的信息

<?xml version="1.0"?>
<!-- script_version=1.1 -->
<robot name="sensor_rplidar" xmlns:xacro="http://ros.org/wiki/xacro">
  <xacro:include filename="$(find turtlebot_description)/urdf/turtlebot_gazebo.urdf.xacro"/>
  <xacro:include filename="$(find turtlebot_description)/urdf/turtlebot_properties.urdf.xacro"/>

  <!-- RPLidar 2D LIDAR -->
  <xacro:macro name="sensor_rplidar" params="parent">
    <joint name="laser" type="fixed">
      <origin xyz="0.15 0.0 0.15" rpy="0 0.0 0.0" />
      <parent link="base_link" />
      <child link="base_laser_link" />
    </joint>

    <link name="base_laser_link">
      <visual>
        <geometry>
          <box size="0.05 0.05 0.05" />
        </geometry>
        <material name="Red" />
      </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 -->
    <rplidar_laser />
  </xacro:macro>
</robot>

3.6.  在<xacro:include filename="$(findturtlebot_description)/urdf/turtlebot_gazebo.urdf.xacro"/>文件下添加配置lasergazebo下的属性值插件配置

<!-- RPLidar LIDAR for simulation -->
  <xacro:macro name="rplidar_laser">
    <gazebo reference="base_laser_link">
      <sensor type="ray" name="laser">
        <pose>0 0 0 0 0 0</pose>
        <visualize>false</visualize>
        <update_rate>5.5</update_rate>
        <ray>
          <scan>
            <horizontal>
              <samples>360</samples>
              <resolution>1</resolution>
              <min_angle>-3.1415926</min_angle>
              <max_angle>3.1415926</max_angle>
            </horizontal>
          </scan>
          <range>
            <min>0.10</min>
            <max>6.0</max>
            <resolution>0.01</resolution>
          </range>
          <noise>
            <type>Gaussian</type>
            <mean>0.0</mean>
            <stddev>0.01</stddev>
          </noise>
        </ray>
        <plugin name="rplidar_node" filename="libgazebo_ros_laser.so">
          <topicName>/scan</topicName>
          <frameName>base_laser_link</frameName>
        </plugin>
      </sensor>
    </gazebo>
  </xacro:macro>

3.7.  环境变量加入

export TURTLEBOT_BASE=kobuki
export TURTLEBOT_STACKS=nostack
export TURTLEBOT_3D_SENSOR=rplidar

运行一致

roslaunch turtlebot_gazebo turtlebot_world.launch
roslaunch turtlebot_gazebo gmapping_demo.launch 
roslaunch turtlebot_rviz_launchers view_navigation.launch 
roslaunch turtlebot_teleop keyboard_teleop.launch 


[置顶] ros中利用gazebo进行gmapping仿真:kobuki+kinct -> kobuki+rplidar_第3张图片

[置顶] ros中利用gazebo进行gmapping仿真:kobuki+kinct -> kobuki+rplidar_第4张图片



[置顶] ros中利用gazebo进行gmapping仿真:kobuki+kinct -> kobuki+rplidar_第5张图片

4.  涉及更改的文件

/home/yhzhao/gmapping_ws/src/turtlebot/turtlebot_description/robots/kobuki_nostack_rplidar.urdf.xacro

<?xml version="1.0"?>
<!-- script_version=1.1 -->
<!--
    - Base      : kobuki
    - Stacks    : nostack
    - 3d Sensor : rplidar
-->    
<robot name="turtlebot" xmlns:xacro="http://ros.org/wiki/xacro">

  <xacro:include filename="$(find turtlebot_description)/urdf/turtlebot_library.urdf.xacro" />
  
  <kobuki/>
  <!--<stack_hexagons parent="base_link"/>-->
  <sensor_rplidar  parent="base_link"/>
</robot>

 /home/yhzhao/gmapping_ws/src/turtlebot/turtlebot_description/urdf/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 turtlebot_description)/urdf/common_properties.urdf.xacro"/>
  <xacro:include filename="$(find turtlebot_description)/urdf/turtlebot_properties.urdf.xacro"/>
  <!-- Bases -->
  <xacro:include filename="$(find create_description)/urdf/create.urdf.xacro"/>
  <xacro:include filename="$(find kobuki_description)/urdf/kobuki.urdf.xacro" />
  <!-- Stacks -->
  <xacro:include filename="$(find turtlebot_description)/urdf/stacks/circles.urdf.xacro"/>
  <xacro:include filename="$(find turtlebot_description)/urdf/stacks/hexagons.urdf.xacro"/>
  <!-- 3D Sensors -->
  <xacro:include filename="$(find turtlebot_description)/urdf/sensors/kinect.urdf.xacro"/>
  <xacro:include filename="$(find turtlebot_description)/urdf/sensors/asus_xtion_pro.urdf.xacro"/>
  <xacro:include filename="$(find turtlebot_description)/urdf/sensors/asus_xtion_pro_offset.urdf.xacro"/>
<xacro:include filename="$(find turtlebot_description)/urdf/sensors/rplidar.urdf.xacro"/>

</robot>

/home/yhzhao/gmapping_ws/src/turtlebot/turtlebot_description/urdf/sensors/rplidar.urdf.xacro

<?xml version="1.0"?>
<!-- script_version=1.1 -->
<robot name="sensor_rplidar" xmlns:xacro="http://ros.org/wiki/xacro">
  <xacro:include filename="$(find turtlebot_description)/urdf/turtlebot_gazebo.urdf.xacro"/>
  <xacro:include filename="$(find turtlebot_description)/urdf/turtlebot_properties.urdf.xacro"/>

  <!-- RPLidar 2D LIDAR -->
  <xacro:macro name="sensor_rplidar" params="parent">
    <joint name="laser" type="fixed">
      <origin xyz="0.15 0.0 0.15" rpy="0 0.0 0.0" />
      <parent link="base_link" />
      <child link="base_laser_link" />
    </joint>

    <link name="base_laser_link">
      <visual>
        <geometry>
          <box size="0.05 0.05 0.05" />
        </geometry>
        <material name="Red" />
      </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 -->
    <rplidar_laser />
  </xacro:macro>
</robot>

/home/yhzhao/gmapping_ws/src/turtlebot/turtlebot_description/urdf/turtlebot_gazebo.urdf.xacro

<?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>


<!-- RPLidar LIDAR for simulation -->
  <xacro:macro name="rplidar_laser">
    <gazebo reference="base_laser_link">
      <sensor type="ray" name="laser">
        <pose>0 0 0 0 0 0</pose>
        <visualize>false</visualize>
        <update_rate>5.5</update_rate>
        <ray>
          <scan>
            <horizontal>
              <samples>360</samples>
              <resolution>1</resolution>
              <min_angle>-3.1415926</min_angle>
              <max_angle>3.1415926</max_angle>
            </horizontal>
          </scan>
          <range>
            <min>0.10</min>
            <max>6.0</max>
            <resolution>0.01</resolution>
          </range>
          <noise>
            <type>Gaussian</type>
            <mean>0.0</mean>
            <stddev>0.01</stddev>
          </noise>
        </ray>
        <plugin name="rplidar_node" filename="libgazebo_ros_laser.so">
          <topicName>/scan</topicName>
          <frameName>base_laser_link</frameName>
        </plugin>
      </sensor>
    </gazebo>
  </xacro:macro>



</robot>


参考:  

gazebo_ros_pkgs  

gazebo :   Connect to ROS    

 turtlebot_simulator

扩展 (仿真器) : vrep_ros_bridge  http://wiki.ros.org/vrep_ros_bridge            http://www.zhihu.com/question/23309094




================

改相机插件的参考gazebo+ros搭建单目仿真环境:贴有二维码的天花板+kobuki+camera(2)

你可能感兴趣的:([置顶] ros中利用gazebo进行gmapping仿真:kobuki+kinct -> kobuki+rplidar)