gazebo的bumper使用

本文解决gazebo的bumper碰撞的时候传感器数据为空的问题。
注意:只有把contact中的collision名字取对了才能有碰撞数据!

使用步骤:
(1)在.urdf.xacro文件中加入link和joint,并且加上碰撞,如给collision命名base_collision

"bumper_link">
    
        "0.0 0.0 0.0" rpy="0 1.0 0"/>
        "0.0000000001"/>
        "0.00000001" ixy="0.00000001" ixz="0.00000001" iyy="0.00000001" iyz="0.00000001" izz="0.00000001"/>
    
    
        "0.0 0.0 0.0" rpy="0.0 1.0 0"/>
        
            "0.01" length="0.01"/>
        
        "red">
            "1.0 0.0 0.0 1.0"/>
        
    
    "base_collision">
        "0.0 0.0 0.0" rpy="0.0 1.0 0.0"/>
        
            "0.01" length="0.01"/>
        
    
  
  "bumper_joint" type="fixed">
      "0.4 0.0 0.1" rpy="0.0 0.0 0.0"/>
      "base_link"/>
      "bumper_link"/>
  

(2)在.gazebo.xacro中加入

"bumper_link">
    "contacts" type="contact">
        
          base_footprint_fixed_joint_lump__base_collision_collision_1
        
        "gazebo_ros_bumper_controller" filename="libgazebo_ros_bumper.so">
          true
          /robot
          bumper_states
          bumper
          true
          50.0        
        
    
    Gazebo/Red
    0.1
    0.1
    true
    false
  

注意这一行一定要命名为如下

base_footprint_fixed_joint_lump__base_collision_collision_1

可以看出命名规则。

如果实在不知道怎么取名字,就用以下命令,在最后生成的urdf文件中找这个名字(如base_collision)

source devel/setup.bash
rosrun xacro xacro --inorder turtlebot3_waffle.urdf.xacro > model.urdf
gz sdf -p model.urdf >model.sdf

碰撞的时候rostopic echo 结果如图
gazebo的bumper使用_第1张图片

参考文献
https://blog.csdn.net/wubaobao1993/article/details/91890839
http://answers.gazebosim.org/question/20432/ros-gazebo-detecting-collision-with-a-static-object-using-contact-sensor/

你可能感兴趣的:(ROS)