ros中利用gazebo进行gmapping仿真:kobuki+kinect -> 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 clone https://github.com/robopeak/rplidar_ros.git
git clone https://github.com/turtlebot/turtlebot_simulator.git
git clone https://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+kinect -> kobuki+rplidar_第1张图片 ros中利用gazebo进行gmapping仿真:kobuki+kinect -> 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

                 

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

       


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

        仿照kobuki_hexagons_kinect.urdf.xacro文件建立

kobuki_nostack_rplidar.urdf.xacro

kobuki_hexagons_rplidar.urdf.xacro




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

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

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




  
  

  
  
    
      
      
      
    

    
      
        
          
        
        
      
      
        
        
        
      
    

    
    
  


3.6.  在文件下添加配置lasergazebo下的属性值插件配置


  
    
      
        0 0 0 0 0 0
        false
        5.5
        
          
            
              360
              1
              -3.1415926
              3.1415926
            
          
          
            0.10
            6.0
            0.01
          
          
            Gaussian
            0.0
            0.01
          
        
        
          /scan
          base_laser_link
        
      
    
  

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+kinect -> kobuki+rplidar_第3张图片

ros中利用gazebo进行gmapping仿真:kobuki+kinect -> kobuki+rplidar_第4张图片



ros中利用gazebo进行gmapping仿真:kobuki+kinect -> kobuki+rplidar_第5张图片

4.  涉及更改的文件

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



    


  
  
  
  
  

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




  
  
  
  
  
  
  
  
  
  
  
  
  



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




  
  

  
  
    
      
      
      
    

    
      
        
          
        
        
      
      
        
        
        
      
    

    
    
  

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



  
  
      
      
        true
        20.0
        
          ${60.0*M_PI/180.0}
          
            R8G8B8
            640
            480
          
          
            0.05
            8.0
          
        
        
          camera
          true
          10
          rgb/image_raw
          depth/image_raw
          depth/points
          rgb/camera_info
          depth/camera_info
          camera_depth_optical_frame
          0.1
          0.0
          0.0
          0.0
          0.0
          0.0
          0.4
        
      
    
  



  
    
      
        0 0 0 0 0 0
        false
        5.5
        
          
            
              360
              1
              -3.1415926
              3.1415926
            
          
          
            0.10
            6.0
            0.01
          
          
            Gaussian
            0.0
            0.01
          
        
        
          /scan
          base_laser_link
        
      
    
  





参考:  

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)

你可能感兴趣的:(【SLAM】,【ROS】)