ros-simulation / gazebo_ros_pkgs

Wrappers, tools and additional API's for using ROS with Gazebo
http://wiki.ros.org/gazebo_ros_pkgs
776 stars 772 forks source link

Cannot remap topic name of the plugin libgazebo_ros_ray_sensor.so #1266

Open chargerKong opened 3 years ago

chargerKong commented 3 years ago

I'm using the libgazebo_ros_ray_sensor.so to publish the topic of laser scan. But it the topic name is strange

Description

<plugin name="gazebo_ros_head_hokuyo_controlle" filename="libgazebo_ros_ray_sensor.so" >
    <ros>
        <namespace>/</namespace>
        <argument>--ros-args --remap out:=scan</argument>                                                                           
    </ros>
    <output_type>sensor_msgs/LaserScan</output_type>
</plugin>

I want the topic name to be /scan, but what it shows out is

/gazebo_ros_head_hokuyo_controlle/out [sensor_msgs/msg/LaserScan]

To Reproduce

Steps to reproduce the behavior: 1.Here is my urdf file content

<gazebo reference="prefix_link">
    <sensor type="ray" name="head_hokuyo_sensor">
        <visualize>true</visualize>
        <update_rate>10</update_rate>
        <ray>
            <scan>
              <horizontal>
                <samples>181</samples>
                <resolution>1</resolution>
                <min_angle>-1.046666667</min_angle>
                <max_angle>1.04666667</max_angle>
              </horizontal>
            </scan>
            <range>
              <min>0.08</min>
              <max>6.0</max>
              <resolution>0.05</resolution>
            </range>
            <noise>
              <type>gaussian</type>
              <mean>0.0</mean>
              <stddev>0.01</stddev>
            </noise>
        </ray>

        <plugin name="gazebo_ros_head_hokuyo_controlle" filename="libgazebo_ros_ray_sensor.so" >
            <ros>
                <namespace>/</namespace>
                <argument>--ros-args --remap out:=scan</argument>                                                                           
            </ros>
            <output_type>sensor_msgs/LaserScan</output_type>
        </plugin>
    </sensor>
</gazebo>
  1. rebuild my package and run the launch file
  2. ros2 topic list -t it returns the name of the laser scan topic is
    /gazebo_ros_head_hokuyo_controlle/out

    Expected behavior

I want the name to be

/scan

Environment (please complete the following information):

AustinDeric commented 3 years ago

try:

<plugin name="gazebo_ros_head_hokuyo_controlle" filename="libgazebo_ros_ray_sensor.so" >
  <ros>
    <remapping>~/out:=/scan</remapping>                                                               
  </ros>
  <output_type>sensor_msgs/LaserScan</output_type>
</plugin>

if confirmed working recommend closing issue. documentation could be improved with respect to URDF files.

chargerKong commented 3 years ago

@AustinDeric Thanks. It works! But I got the warning from gzserver that makes me uncomfortable

[gzserver-1] [WARN] [1619332042.212865893] [rcl]: Found remap rule '~/out:=/scan'. This syntax is deprecated. Use '--ros-args --remap ~/out:=/scan' instead.

The key problem is that the recommended syntax does not work :sweat_smile:

jnd4i-aj commented 3 months ago

I'm also trying the same but it's not showing the topic name even when I don't remap when I run the ros2 topic list -t

The output of ros2 topic list -t

/clicked_point [geometry_msgs/msg/PointStamped]
/clock [rosgraph_msgs/msg/Clock]
/cmd_vel [geometry_msgs/msg/Twist]
/goal_pose [geometry_msgs/msg/PoseStamped]
/initialpose [geometry_msgs/msg/PoseWithCovarianceStamped]
/joint_states [sensor_msgs/msg/JointState]
/odom [nav_msgs/msg/Odometry]
/parameter_events [rcl_interfaces/msg/ParameterEvent]
/performance_metrics [gazebo_msgs/msg/PerformanceMetrics]
/robot_description [std_msgs/msg/String]
/rosout [rcl_interfaces/msg/Log]
/tf [tf2_msgs/msg/TFMessage]
/tf_static [tf2_msgs/msg/TFMessage]

And my plugin is

<gazebo reference="lidar_link">
        <material>Gazebo/FlatBlack</material>
        <sensor type="ray" name="lidar_sensor">
            <pose>0 0 0 0 0 0</pose>
            <visualize>true</visualize>
            <update_rate>10</update_rate>
            <ray>
                <scan>
                    <horizontal>
                        <samples>360</samples>
                        <resolution>1</resolution>
                        <min_angle>0.0</min_angle>
                        <max_angle>6.28319</max_angle>
                    </horizontal>
                </scan>
                <range>
                <min>0.120</min>
                <max>3.5</max>
                <resolution>0.015</resolution>
                </range>
                <noise>
                    <type>gaussian</type>
                    <mean>0.0</mean>
                    <stddev>0.01</stddev>
                </noise>
            </ray>
            <plugin name="gazebo_ros_rplidar" filename="libgazebo_ros_ray_sensor.so">
                <topicName>/ray/pointcloud2</topicName>
                <frameName>lidar_link</frameName>
            </plugin>
        </sensor>
    </gazebo>

What can be the issue? Thanks in advance:)