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

Using Hokuyo Lidar on model in Gazebo-7 and RViz

asked 2020-02-14 14:06:32 -0500

John999991 gravatar image

updated 2020-02-15 05:51:31 -0500

Dear all, I am trying to add a Lidar (Hokuyo) on my model using the following configuration:

-- ROS Kinetic

-- Gazebo 7.0

-- Ubuntu 16.04

The code I added at the URDF file is:

  <link name="lidar">
    <inertial>
      <origin xyz="0 0 0.01" rpy="0 0 0" />
      <mass value="0.01" />
      <inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6" />
    </inertial>
    <visual>
      <origin xyz="0 0 0.005" rpy="0 0 0" />
      <geometry>
        <cylinder radius="0.01" length="0.01"/>
      </geometry>
      <material name="">
        <color rgba="0 0 0 1" />
      </material>
    </visual>
    <collision>
      <origin xyz="0 0 0" rpy="0 0 0" />
      <geometry>
        <cylinder radius="0.01" length="0.01"/>
      </geometry>
    </collision>
  </link>


  <joint name="TB_Lidar" type="fixed">
  <axis xyz="0.0 0.0 1.0"/>
    <parent link="TB"/>
    <child link="lidar"/>
    <origin xyz="0 0 0" rpy="0.0 0.0 0.0" />
  </joint>

  <gazebo>

    <gazebo reference = "laser_scanner">
       <sensor type="ray" name="head_hokuyo_sensor"> 
        <pose> 0 0 0 0 0 0 </pose>
        <visualize>true</visualize>
        <update_rate>40</update_rate>
        <ray>
          <scan>
            <horizontal>
              <samples>720</samples>
              <resolution>1</resolution>
              <min_angle>-1.578</min_angle>
              <max_angle>1.578</max_angle>
            </horizontal>
          </scan>
          <range>
            <min>0.1</min>
            <max>30</max>
            <resolution>0.1</resolution>
          </range>
        </ray>
         <plugin name="gpu_laser" filename="libgazebo_ros_gpu_laser.so">
          <topicName>/scan</topicName>
          <frameName>laser_scanner</frameName>
        </plugin>
      </sensor>
    </gazebo>

But I cannot see the /scan topic or any publishers at this topic. The Lidar is not working. Any Ideas why?

edit retag flag offensive close merge delete

Comments

I have located the libgazebo_ros_laser.so at /opt/ros/kinetic/lib/

John999991 gravatar image John999991  ( 2020-02-15 05:50:30 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
0

answered 2020-02-15 11:25:08 -0500

John999991 gravatar image

updated 2020-02-15 13:12:26 -0500

ok, so apparently the problems were:

<plugin name="gpu_laser" filename="libgazebo_ros_gpu_laser.so">

I cannot use the gpu version for some reason... The correct (that worked for me) was:

<plugin filename="libgazebo_ros_laser.so" name="gazebo_ros_head_hokuyo_controller">

Next:

 <!-- Hokuyo Laser -->
 <link name="hokuyo_link">
    <collision>
      <origin xyz="0 0 0" rpy="0 0 0" />
      <geometry>
        <box size="0.01 0.01 0.01"/>
      </geometry>
    </collision>
  </link>

Here I used <link name="lidar"> which doesn't match the one from <gazebo reference="hokuyo_link">. Further more on the same <link>, I defined the <inertial> and <visual> part which was also not expected. Only the <collision> should be present.

Finally also the <plugin name="gpu_laser" filename="libgazebo_ros_gpu_laser.so"> could be a problem since i think Gazebo expects <plugin filename="libgazebo_ros_laser.so" name="gazebo_ros_head_hokuyo_controller"> but not 100% sure about that.

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2020-02-14 14:06:32 -0500

Seen: 1,116 times

Last updated: Feb 15 '20