学习笔记19 --gazebo仿真使用的bumper传感器无数据输出问题解决

环境:ubnutu16.04 ros-kinetic gazebo7.16

问题:在urdf添加了仿真时候用的碰撞传感器bumper(这个是gazebo本身自带的,直接在urdf里面声明就可以使用了),但是无论怎么碰撞测试,该topic都是没有数据输出的.

原因有:
1)定义的传感器没有裸露在外侧,没有办法和外界接触
2)排除了1)的可能性后,就是在urdf定义该传感器问题了:gazebo-sensor-contact-collision 没有指定定义bumper的link的sdf中的collision名称.

解决方式补全原因2)的名称,下面用案例来展示:

<link name="base_link"/>
<joint name="bumper_joint" type="fixed">
    <origin xyz="1 0 0" rpy="0 0 0"/>
    <parent link="base_link"/>
    <child link="bumper_link"/>
</joint>
<link name="bumper_link">
    <visual>
        <origin xyz="0 0 0" rpy="0 0 0"/>
        <geometry>
            <box size="0.01 0.1 0.1"/>
        </geometry>
    </visual>
    <collision>
        <origin xyz="0 0 0" rpy="0 0 0"/>
        <geometry>
            <box size="0.01 0.1 0.1"/>
        </geometry>
    </collision>
    <inertial>
        <mass value="0.1"/>
        <origin xyz="0 0 0" rpy="0 0 0"/>
        <inertia ixx="1000" ixy="0" ixz="0" iyy="1000" iyz="0" izz="1000"/>
    </inertial>
</link>
<gazebo reference="bumper_link">
    <sensor type="contact" name="bumper">
        <always_on>true</always_on>
        <update_rate>1000.0</update_rate>
        <visualize>true</visualize>
        <contact>
        //重点获取该collision名称
            <collision>base_link_joint_lump__bumper_link_collision_1</collision>
        </contact>
        <plugin name="gazebo_ros_bumper_controller" filename="libgazebo_ros_bumper.so">//gazebo自带的bumper插件调用样式
            <updateRate>100</updateRate>
            <bumperTopicName>bumper</bumperTopicName>
            <frameName>base_link</frameName>
        </plugin>
    </sensor>
</gazebo>

我们一般没有办法直接看出来,定义的该有碰撞属性的link在gazebo里面,其中的collision名称叫什么,但是我们可以使用工具:

//注意如果是xacro格式的,先使用rosrun xacro xacro a.xacro>a.urdf转为urdf格式先
gz sdf -p a.urdf >a.sdf

将我们的urdf转为sdf格式,根据我们定义的link名称以及父link名称来确定该link的collision在sdf里面叫什么,然后截取该名称填写到gazebo-sensor-contact-collision 中,碰撞测试,该bumper 的 topic就可以有输出了.

下面是个人该bumper的link的collision名称截取部分样式:

  <collision name='base_link_joint_lump__bumper_link_collision_1'>
  //上面这个标签名称就是我们想要的,截取并填写到urdf里面的gazebo-sensor-contact-collision位置上
    <pose frame=''>1 0 0 0 -0 0</pose>
    <geometry>
      <box>
        <size>0.01 0.1 0.1</size>
      </box>
    </geometry>
    <surface>
      <contact>
        <ode/>
      </contact>
      <friction>
        <ode/>
      </friction>
    </surface>
  </collision>

至此,我们就可以解决了gazebo仿真时候,引用gazebo自带的bumper碰撞传感器没有数据输出的问题.

你可能感兴趣的:(ROS/gazebo)