ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
1

Gazebo laser plug-in fails to publish scan results in rviz

asked 2016-01-18 13:12:42 -0500

Kishore Kumar gravatar image

updated 2016-01-20 09:14:26 -0500

I have added differential drive plug-in and laser sensor (hokuyo) plug-in to my urdf file. I launched the robot in environment shown below and moved the robot using tele-operation. image description

Then i launched the rviz and did the setup required to view the scan results fron laser plug-in but it failed (refer the pic below).

image description

Following are my terminal result and result for rostopic echo /scan respectively. image description

image description

Where have i gone wrong how to fix this, does the warnings in terminal cause this problem?

Below is my plug-in code

Link:

<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.055 0.2" rpy="0 0 0"/>
    <parent link="Base_plate"/>
    <child link="hokuyo_link"/>
  </joint>

laser Controller

<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>100</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>

My RQT result

image description

edit retag flag offensive close merge delete

Comments

Have you used RQT to look at the TF graph? Is it complete from the odom frame to the hokuyo_link frame?

jeremya gravatar image jeremya  ( 2016-01-18 14:03:56 -0500 )edit

Yes, it seems to be fine. Please refer it above in my last edit.

Kishore Kumar gravatar image Kishore Kumar  ( 2016-01-19 03:11:16 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
2

answered 2016-01-20 11:16:38 -0500

It's rather unusual to only have 0.0 ranges in the scan message. This also pretty much rules out issues due to rays hitting the inside of the laser box geometry and therefore not appearing in the scene.

I'd first test if the situation is different with the standard (not GPU) sensor. I've seen graphics driver related issues with the gpu ray sensor before, so it's a good idea to test for that. For the differences between both you can have a look at hokuyo_utm30lx.urdf.xacro. This macro contains both a gpu and non-gpu script. If the non-gpu sensor works, you're looking at a graphics card/driver compatibility problem.

edit flag offensive delete link more

Comments

yes, non-gpu version works fine for me. How to root cause the graphics issue and fix it?

Kishore Kumar gravatar image Kishore Kumar  ( 2016-01-21 00:03:35 -0500 )edit
1

Running OGRE-based rviz and gazebo on non-nvidia cards is problematic since the "dawn of time" :) and there is no general solution. You can try using updated graphics drivers and such, but there's not silver bullet to solve the problem. Search for "gazebo"+ your graphics card type here and on google

Stefan Kohlbrecher gravatar image Stefan Kohlbrecher  ( 2016-01-21 01:33:14 -0500 )edit

I am using AMD graphics card, does it be the culprit?

Kishore Kumar gravatar image Kishore Kumar  ( 2016-01-21 04:53:53 -0500 )edit

Yes. If you have a dual graphics setup you could try using your other GPU. Otherwise your could try instaling a newer driver or so, but there are no guarantees for improvement.

Stefan Kohlbrecher gravatar image Stefan Kohlbrecher  ( 2016-01-21 08:01:30 -0500 )edit

What would you suggest if the the non-GPU laser didn't work? I'm having an identical problem to this and when I tried to use the non-GPU laser I recived the following error: Controller Spawner couldn't find the expected controller_manager ROS interface.

bob gravatar image bob  ( 2016-06-11 08:48:56 -0500 )edit

Any update running gpu_laser on non-nvidia?

achmad_fathoni gravatar image achmad_fathoni  ( 2018-06-02 02:23:51 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2016-01-18 13:12:42 -0500

Seen: 3,050 times

Last updated: Jan 20 '16