Gazebo isn't seeing obstacles with a laser scanner

asked 2021-01-29 15:01:58 -0600

BesterJester gravatar image

I'm creating my robot model with a URDF file. I've added in the below snippet of code to model the laser scanner.

  <link name="hokuyo_link">
<collision>
  <origin xyz="0 0 0" rpy="0 0 0"/>
  <geometry>
    <box size="0.1 0.1 0.1"/>
  </geometry>
</collision>
<visual>
  <origin xyz="0 0 0" rpy="0 0 0"/>
  <geometry>
    <box size="0.1 0.1 0.1"/>
  </geometry>
</visual>
<inertial>
  <mass value="1e-5" />
  <origin xyz="0 0 0" rpy="0 0 0"/>
  <inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6" />
</inertial>
</link>

<joint name="hokuyo_joint" type="fixed">
<axis xyz="0 1 0" />
<origin xyz="0 0 0.2" rpy="0 0 0"/>
<parent link="base_link"/>
<child link="hokuyo_link"/>
</joint>

<gazebo reference="hokuyo_link">
<sensor type="gpu_ray" name="hokuyo">
  <pose>0 0 0 0 0 0</pose>
  <visualize>false</visualize>
  <update_rate>40</update_rate>
  <ray>
    <scan>
      <horizontal>
        <samples>720</samples>
        <resolution>1</resolution>
        <min_angle>-1.570796</min_angle>
        <max_angle>1.570796</max_angle>
      </horizontal>
    </scan>
    <range>
      <min>0.10</min>
      <max>30.0</max>
      <resolution>0.01</resolution>
    </range>
  </ray>
  <plugin name="gpu_laser" filename="libgazebo_ros_gpu_laser.so">
    <topicName>/scan</topicName>
    <frameName>hokuyo_link</frameName>
  </plugin>
</sensor>

</gazebo>

This should enable my model to start publishing the resulting laser data onto the scan topic. I run my model in a Gazebo world and the world includes obstacles. I see from rostopic echo /scan that it is publishing laser data on the scan topic. However, it always publishes data points at the maximum length of the scan, as if it never sees anything. I've driven my robot all around the obstacles but with no change to the laser data. Am I doing something wrong with the above sensor code? Do I need to change some setting in Gazebo so it recognizes the obstacles?

Linux 5.3.0-62-generic #56 18.04.1-Ubuntu

edit retag flag offensive close merge delete