阿克曼结构移动机器人的gazebo仿真(五)

阿克曼结构移动机器人的gazebo仿真(五)

第四章、用xacro优化URDF并配置gazebo仿真插件

0.前言

上节用简易模型写了一个小车的URDF代码,这一节将用xacro对其进行优化,这里我并不打算用宏对参数进行封装,因为我个人觉得这样看起来会比较直观,方便读者阅读。

1.配置主xacro文件

新建racecar.xacro文件,将上一节racebot.urdf中的代码复制过来并进行修改,整体代码如下:





    
    
    
    

    
        
            
                
                
            
            
            
            
                
            
        
        
            
                
            
            
        

    

    
        
        
        
    




    
    
            
            
            
        
    

    
    
    
    
    
  




    
        
            
                
                
            
            
            
                
            
        
        
            
                
                
            
            
        
        
            
            
            
        
    


    
        
        
        
        
        
    
    





    
        
            
                
            
            
            
                
            
        
        
            
                
            
            
        
        
            
            
            
        
    

    
        
        
        
        
        
    
     





        
            
                 
            
            
            
                
            
        
        
            
                
            
            
        
        
            
            
            
        
    

    
        
        
        
        
        
    
    






     
        
            
                
            
            
            
                
            
        
        
            
                
            
            
        
        
            
            
            
        
    

    
        
        
        
        
        
    
    



    
        
            
                
            
            
            
                
            
        
        
            
                
            
            
        
        
            
            
            
        
    

    
        
        
        
        
        
    
    



    
        
            
                
            
            
            
                
            
        
        
            
                
            
            
        
        
            
            
            
        
    

    
        
        
        
        
        
    
    

    
        
            
                
            
            
            
                
            
        
        
            
                
            
            
        
        
            
            
            
        
    

    
        
        
        
        
    



    
        
            
                
            
            
            
                
            
        
        
            
                
            
            
        
        
            
            
            
        
    

    
        
        
        
        
    


    
        
            
                
            
            
            
                
            
        
        
            
                
            
            
        
        
            
            
            
        
    

    
        
        
        
        
    

    
        
            
                
            
            
            
                
            
        
        
            
                
            
            
        
        
            
            
            
        
    

    
        
        
        
        
    

  


代码起始和末尾添加了两个文件,通过xacro封装引用进来。这两个xacro文件是接下去要配置的传动文件macros.xacro以及gazebo插件racecar.gazebo。

2.添加传动transmission

创建macro.xacro文件,该代码给前后轮以及前轮摆转配置了传动transmission元素,代码如下:







  
    transmission_interface/SimpleTransmission
    
      hardware_interface/EffortJointInterface
    
    
      hardware_interface/EffortJointInterface
      1
    
  



  
    transmission_interface/SimpleTransmission
    
      hardware_interface/EffortJointInterface
    
    
      hardware_interface/EffortJointInterface
      1
    
  



值得注意的是,引用该文件时,要将路径代码放置到racecar.xacro代码的最上端位置,如上代码所示,否则将无法引用到,并且在需要添加传动的link后面添加宏定义,以左前轮以及左前轮摆转为例:

 
 .
 .
 .
 

3.配置gazebo插件

要让小车在gazebo中仿真,并且让小车能够进行建图导航,需要给小车的摄像头,激光雷达等link添加传感器插件,下面将进行配置,新建racecar.gazebo文件,开头代码:



。
。
。

配置各个link的颜色:

由于车轮实际上会接触地面,因此会与地面发生物理相互作用,将各个link添加部件材料的附加信息,并且定义各个link的颜色信息。参考

gazebo官网




  
  
  
  
  Gazebo/Red



  
  
  
  
  
  Gazebo/Black



  
  
  
  
  
  Gazebo/Black



  
  
  
  
  
  Gazebo/Black



  
  
  
  
  
  Gazebo/Black



  Gazebo/Black



  Gazebo/Black



  Gazebo/Grey

配置ros_control

由于gazebo并没阿克曼车型的插件,要链接gazebo与ros,我们先添加ros_control插件,它读取所有transmission标记,以及joint_state_publisher插件



  
    /racebot
    robot_description
    gazebo_ros_control/DefaultRobotHWSim
    true
  

值得注意的是命名空间要设置为/racebot。

配置激光雷达插件:



  
    Gazebo/Grey
    
      0 0 0.0124 0 0 0
      false
      40
      
        
          
            1081
            1
            -2.3561944902
            2.3561944902
          
        
        
          0.1
          10.0
          0.01
        
        
          0.0
          0.01
        
      
      
        /scan
        lidar
      
    
  

配置深度相机插件:

由于配置realsense插件过于复杂,因此这里用kinect插件来代替realsense插件。


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

配置单目相机插件:



  Gazebo/Grey
    
      30.0
      
        1.3962634
        
          800
          800
          R8G8B8
        
        
          0.02
          300
        
        
          gaussian
          0.0
          0.007
        
      
      
        true
        0.0
        rrbot/camera1
        image_raw
        camera_info
        camera
        0.07
        0.0
        0.0
        0.0
        0.0
        0.0
      
    

配置imu插件:


        Gazebo/Orange
        true
        
            true
            100
            true
            __default_topic__
            
                imu
                imu
                100.0
                0.0
                0 0 0
                0 0 0
                imu_link
            
            0 0 0 0 0 0
        

4.在gazebo中显示并演示传感器效果

创建racebot_gazebo功能包,并创建如下文件夹:

阿克曼结构移动机器人的gazebo仿真(五)_第1张图片

在launch文件夹中创建racebot.launch文件:



	    
    
    
    
    
    
    
    
    
    
    
    
    

	
	
        	
        	
        	
        	
        	
	        
               
    	

	
	

  	    
     
    
          
  

    






在worlds文件夹中,将之前用于mini小车仿真的room_mini.world文件放入,使得racebot载入有room_mini地图的gazebo仿真环境中。

roslaunch racebot_gazebo racebot.launch

阿克曼结构移动机器人的gazebo仿真(五)_第2张图片
阿克曼结构移动机器人的gazebo仿真(五)_第3张图片

可以看到小车已经加载到gazebo环境中,然而此时无法控制小车运动,因为还未配置controllers,但是我们可以读取到传感器参数。

读取imu参数:

rostopic echo /imu

阿克曼结构移动机器人的gazebo仿真(五)_第4张图片

读取雷达数据:

打开rviz

rviz

将fixed_frame改为base_footprint, 点击add–>by topic–>laserScan,此时在rviz中即可显示雷达点云
阿克曼结构移动机器人的gazebo仿真(五)_第5张图片
阿克曼结构移动机器人的gazebo仿真(五)_第6张图片

单目摄像头:

在rviz中add–>by topic–>/rrbot/camera1/image_raw/camera即可添加相机插件,并显示图像:
阿克曼结构移动机器人的gazebo仿真(五)_第7张图片

深度摄像头:

深度摄像头查看深度图像与单目摄像头同理add–>by topic–>realsense/depth/image_raw/camera
阿克曼结构移动机器人的gazebo仿真(五)_第8张图片

只是在添加pointcloud2时会出现问题,add–>by topic–>realsense/depth/points/pointcloud2,会发现彩色点云出现在小车正上方,原因是在kinect中图像数据与点云数据使用了两套坐标系统,且两套坐标系统位姿并不一致。

阿克曼结构移动机器人的gazebo仿真(五)_第9张图片

解决方法有两种

1.可以在launch文件中加入坐标变换,即可解决这一现象。


详细参考,奥特学园

2.第二种方法是在urdf中加入新的link,即使用点云数据的link,并通过joint做坐标变换来解决

    
    
            
            
            
    

修改插件


      
          true
          20.0
          
              ${60.0*3.14/180.0}
              
                  R8G8B8
                  640
                  480
              
              
                  0.05
                  8.0
              
          
          
              real_sense
              true
              10
              rgb/image_raw
              depth/image_raw
              depth/points
              rgb/camera_info
              depth/camera_info
              realsense_depth
              0.1
              0.0
              0.0
              0.0
              0.0
              0.0
              0.4
          
      
  

阿克曼结构移动机器人的gazebo仿真(五)_第10张图片

小结

本节内容关于小车传动的添加,以及配置了小车上面的一些插件,下一节内容,通过配置controller让小车动起来。

参考资料

1.古月老师的<>

2.奥特学园

3.gazebo官网

你可能感兴趣的:(ROS学习,阿克曼小车仿真,人工智能)