Robotics StackExchange | Archived questions

ROS plugin - SDF empty robotNamespace

I've built up a robot model robotino.sdf(see below) which uses the slightly modified myhokuyo.sdf laser scanner model (see below, just added the ros-laser plugin).

Now if I start gazebo with roslaunch gazebo_ros empty_world.launch and add the robot model, I get this output:

[ INFO] [1424682979.068295221, 7.402000000]: Laser Plugin (robotNamespace = ), Info: the 'robotNamespace' param did not exit
[ INFO] [1424682979.068369479, 7.402000000]: Starting Laser Plugin (ns = )!
[ INFO] [1424682979.069371065, 7.403000000]: Laser Plugin (ns = )  <tf_prefix_>, set to ""

rostopic list outputs:

/clock
/gazebo/link_states
/gazebo/model_states
/gazebo/parameter_descriptions
/gazebo/parameter_updates
/gazebo/set_link_state
/gazebo/set_model_state
/laser_scan
/rosout
/rosout_agg

How can I define the robotNamespace within robotino.sdf so that the laserscan topic is published under `/robotinobbu/laser_scan`?

I need different topics since there will be multiple instances of the same model in one simulation.


robotino.sdf file:

<?xml version="1.0" ?>
<sdf version="1.4">

    <model name="robotino_bbu">

    <include>
      <uri>model://robotino3</uri>
      <pose>0 0 0 0 0 0</pose>
    </include>


    <include>
      <uri>model://myhokuyo</uri>
      <pose>0.0 -0.15 0.235 0 0 -1.570796</pose>
    </include>

    <joint name="hokuyo_joint" type="revolute">
      <parent>robotino3::body</parent>
      <child>myhokuyo::link</child>
      <axis>
        <xyz>0 0 1</xyz>
        <limit>
          <upper>0</upper>
          <lower>0</lower>
        </limit>
      </axis>
    </joint>

    <plugin name="Odometry" filename="libodometry.so"/>

  </model>
</sdf>

myhokuyo.sdf

<?xml version="1.0" ?>
<sdf version="1.4">
  <model name="myhokuyo">
    <pose>0 0 0.035 0 0 0</pose>
    <link name="link">
      <inertial>
        <mass>0.1</mass>
      </inertial>
      <visual name="visual">
        <geometry>
          <mesh>
            <uri>model://hokuyo/meshes/hokuyo.dae</uri>
          </mesh>
        </geometry>
      </visual>

      <collision name="collision-base">
        <pose>0 0 -0.0145 0 0 0</pose>
        <geometry>
          <box>
            <size>0.05 0.05 0.041</size>
          </box>
        </geometry>
      </collision>

      <collision name="collision-top">
        <pose>0 0 0.0205 0 0 0</pose>
        <geometry>
          <cylinder>
            <radius>0.021</radius>
            <length>0.029</length>
          </cylinder>
        </geometry>
      </collision>


      <sensor name="laser" type="ray">
        <pose>0.01 0 0.0175 0 -0 0</pose>
        <ray>
          <scan>
            <horizontal>
              <samples>640</samples>
              <resolution>1</resolution>
              <min_angle>-2.26889</min_angle>
              <max_angle>2.268899</max_angle>
            </horizontal>
          </scan>
          <range>
            <min>0.08</min>
            <max>10</max>
            <resolution>0.01</resolution>
          </range>
        </ray>

        <plugin name="laser" filename="libRayPlugin.so" />
    <plugin name="link_laser_controller" filename="libgazebo_ros_laser.so">
            <topicName>laser_scan</topicName>
            <frameName>link</frameName>
    </plugin>
        <always_on>1</always_on>
        <update_rate>30</update_rate>
        <visualize>true</visualize>
      </sensor>
    </link>
  </model>
</sdf>

Asked by SailAvid on 2015-02-23 04:43:13 UTC

Comments

what is the state of this question? is it fixed?

Asked by zesaro on 2018-01-10 04:49:51 UTC

Answers

Try using robotino_bbu within ....

Asked by slivingston on 2015-03-01 03:41:33 UTC

Comments

That would assign a specific topic to the Hokuyo model. So if I add the Hokuyo to another robot, the topic name would be identical. I need to define the robotNamespace somehow in the robotino model file, as mentioned in my question.

Asked by SailAvid on 2015-03-03 03:43:32 UTC

Try using group tags in your launchfile, it worked for me automatically. Do not set robot namespace, in urdf otherwise they are not set by the group in the launch file.

Asked by cyborg_x1 on 2015-03-09 06:45:30 UTC

Comments

Can you add an example for the launchfile? Because I tried this already and it didn't work...

Asked by SailAvid on 2015-03-11 10:29:49 UTC

See in my repository ... just fixed it. Be also sure not to write /topic ! Write topic as name instead. The / means "root". https://github.com/cyborg-x1/rapid_robot_xacros/blob/master/launch/multi_diff_drive_bot.launch

Asked by cyborg_x1 on 2015-03-11 14:27:40 UTC

I also had the same problem, but the other answers didn't work for me. I solved the issue by declaring an empty robotNamespace tag inside the plugin tag

<!-- hokuyo_model.sdf -->
...
<plugin name="laser_controller" filename="libgazebo_ros_laser.so">
  <robotNamespace></robotNamespace>
  <topicName>sensor</topicName>
  <frameName>link</frameName>
</plugin>
...

Then, if you attach it to a robot

<!-- my_robot_with_laser.sdf -->

<?xml version="1.0" ?>
<sdf version="1.5">
  <model name="pioneer3at">

    <include>
      <uri>model://pioneer3at</uri>
    </include>

    <include>
      <uri>model://hokuyo</uri>
      <pose>0 0 0.3 0 0 0</pose>
    </include>

    <joint name="laser_joint" type="revolute">
      <parent>pioneer3at::chassis</parent>
      <child>hokuyo::link</child>
      <axis>
        <xyz>0 0 1</xyz>
        <limit>
          <lower>0</lower>
          <upper>0</upper>
        </limit>
      </axis>
    </joint>

    ... <!-- maybe other plugins -->

  </model>
</sdf>

it will make the sensor take the name of the model on which is attached as its namespace when spawning the model from a launch file

<launch>
  ...
  <group ns="my_namespace">
    <node pkg="gazebo_ros" type="spawn_model"
          respawn="false"
          name="spawn_model"
          args="-file my_robot_with_laser.sdf -sdf -model my_namespace" />

    ... <!-- maybe other nodes -->
  </group>
  ...
</launch>

Be aware that the group tag doesn't have any effect over the Hokuyo sensor ( it's the -model my_namespace what's doing the trick), but you'll need it if you have other plugins or nodes defined and want them to be namespaced.

Asked by yarox on 2015-05-26 09:12:50 UTC

Comments