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

gazebo_ros range plugin do not show in rostopic list

asked 2022-05-24 06:23:45 -0500

benasking7124 gravatar image

updated 2022-07-10 12:10:31 -0500

lucasw gravatar image

Hi,

I am trying to implement a sonar sensor in Gazebo. I search online and find this tutorial.

I follow the instruction and make some change because I use Noetic instead of Kinetic. After setting up, I get a strange result. I can see the sonar link attached to the rover but when I do rostopic list, I cannot find the topic the plugin should publish.

Here is the sonar part of my xacro file:

And here is the sonar part of my .gazebo file:

<joint name="sonar_front_joint" type="fixed">
   <axis xyz="0 1 0" />
   <origin rpy="0 0 0" xyz="0.5 0 0.25" />
   <parent link="base_footprint"/>
   <child link="base_sonar_front"/>
</joint>
<link name="base_sonar_front">
   <collision>
     <origin xyz="0 0 0" rpy="0 0 0"/>
     <geometry>
       <box size="0.01 0.01 0.01"/>
     </geometry>
   </collision>
   <visual>
     <origin xyz="0 0 0" rpy="0 0 0"/>
     <geometry>
       <box size="0.01 0.01 0.01"/>
     </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>

And here is the launch file:

<launch>
    <arg name="world" default="basic.world"/> 
    <arg name="paused" default="false"/>
    <arg name="use_sim_time" default="true"/>
    <arg name="gui" default="true"/>
    <arg name="headless" default="false"/>
    <arg name="debug" default="false"/>

    <include file="$(find gazebo_ros)/launch/empty_world.launch">
     <arg name="world_name" value="$(find rover_gazebo)/worlds/$(arg world)"/>
     <arg name="paused" value="$(arg paused)"/>
     <arg name="use_sim_time" value="$(arg use_sim_time)"/>
     <arg name="gui" value="$(arg gui)"/>
     <arg name="headless" value="$(arg headless)"/>
     <arg name="debug" value="$(arg debug)"/>
     <arg name="verbose" value="false"/>
    </include>
</launch>

I'm using ROS Noetic and Gazebo 11. And I have checked the libgazebo_ros_range.so exists.

Thank you

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
1

answered 2022-05-25 03:42:23 -0500

aarsh_t gravatar image

Please read whole tutorial, scroll down to bottom. You need to add the plugin in the URDF it is not an automatic process.

You are missing these things in your URDF

<gazebo reference="base_ir_front">        
   <sensor type="ray" name="TeraRanger">
      <pose>0 0 0 0 0 0</pose>
      <visualize>true</visualize>
      <update_rate>50</update_rate>
      <ray>
         <scan>
            <horizontal>
               <samples>10</samples>
               <resolution>1</resolution> 
               <min_angle>-0.14835</min_angle>
               <max_angle>0.14835</max_angle>
            </horizontal>
            <vertical>
               <samples>10</samples>
               <resolution>1</resolution> 
               <min_angle>-0.14835</min_angle>
               <max_angle>0.14835</max_angle> 
            </vertical>
         </scan>
         <range>
            <min>0.01</min>
            <max>2</max>
            <resolution>0.02</resolution>
         </range>
      </ray>
      <plugin filename="libgazebo_ros_range.so" name="gazebo_ros_range">
         <gaussianNoise>0.005</gaussianNoise>
         <alwaysOn>true</alwaysOn>
         <updateRate>50</updateRate>
         <topicName>sensor/ir_front</topicName>
         <frameName>base_ir_front</frameName>
         <radiation>INFRARED</radiation>
         <fov>0.2967</fov>
      </plugin>
   </sensor>  
   </gazebo>
edit flag offensive delete link more
1

answered 2022-05-25 03:49:37 -0500

Joe28965 gravatar image

You haven't actually added the sensor or plugin to your link.

You have created the link, but nothing more, just a link.

Links in ROS are nothing more than saying telling ROS (your software): This component is located here relative to my other components. Comparing that to the real world. Let's say you've got a sonar and you've added it to your turtlebot. Your sonar ROS driver will create a message saying something like (partial message):

Header:
    seq
    timestamp
    frame_id
...

The frame_id is something you can often configure as a parameter. In your case, you would like it to (probably) be base_sonar_front.

That way, if some other node in ROS needs that sonar data, it can use the tf tree to see how the sensor is connected to the rest of the robot (if the sensor is on a 1m pole sticking forward, the data needs to be interpreted a lot differently than when it's directly in the center of rotation for instance).

What you've done is added the link, which will places your sonar data relative to the rest of the robot. What you haven't done is add the actual sensor to it in Gazebo (basically, you've told ROS where you want the sensor to be, but it's still lying on your virtual shelf).

Looking at the link you've send, they do this at the heading called Adding the sensor plugin for Sonar and IR.

  <ray>
     <scan>
        <horizontal>
           <samples>10</samples>
           <resolution>1</resolution> 
           <min_angle>-0.14835</min_angle>
           <max_angle>0.14835</max_angle>
        </horizontal>
        <vertical>
           <samples>10</samples>
           <resolution>1</resolution> 
           <min_angle>-0.14835</min_angle>
           <max_angle>0.14835</max_angle> 
        </vertical>
     </scan>
     <range>
        <min>0.01</min>
        <max>2</max>
        <resolution>0.02</resolution>
     </range>
  </ray>

That ^ part adds the sensor (so actually mounting it to your robot and not leaving it on your shelf)

  <plugin filename="libgazebo_ros_range.so" name="gazebo_ros_range">
     <gaussianNoise>0.005</gaussianNoise>
     <alwaysOn>true</alwaysOn>
     <updateRate>50</updateRate>
     <topicName>sensor/ir_front</topicName>
     <frameName>base_ir_front</frameName>
     <radiation>INFRARED</radiation>
     <fov>0.2967</fov>
  </plugin>

The plugin part can be seen like the driver. You have added the sensor to Gazebo (mounted it on your robot), but you until you add the plugin part, you aren't actually running the driver to publish the data in ROS.

Since I don't know your level of expertise in simulations, I hope my real world comparisons helped you understand exactly what's going on. If you need any more clarification, please let me know.

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2022-05-24 06:18:19 -0500

Seen: 370 times

Last updated: May 25 '22