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 laser_scan topic is published under /robotino_bbu/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>
what is the state of this question? is it fixed?