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

Issue subscribing to topic that is populated from libgazebo_ros_ray_sensor.so

asked 2021-04-26 12:24:01 -0500

user300 gravatar image

I have created a ray sensor in my Gazebo SDF file. This sensor includes the following plugin defined:

    <plugin name="aft_stbd_plugin" filename="libgazebo_ros_ray_sensor.so">
      <ros>
        <!-- Configure namespace and remap to publish to /ray/range -->
        <namespace>/ray</namespace> 
        <remapping>~/out:=range</remapping>
      </ros>

      <output_type>sensor_msgs/Range</output_type>
      <radiation_type>ultrasound</radiation_type>
    </plugin>

In my ROS2 node c++ file, i use the following to subscribe to the /ray/range topic:

ray_sub = this->create_subscription<sensor_msgs::msg::range>( "ray/range", 1, std::bind(&DVL::setRayData, this, std::placeholders::_1));

I put a simple print statement in the setRayData() function. When I run my test world with the ray sensor model and my ROS2 node, it never makes it to the setRayData() function.

In a terminal: ros2 topic list has /ray/range included ros2 topic echo /ray/range shows the data and it is updating at the appropriate rate

Am I missing something unique that may be needed in the node when using the gazebo_ros sensor plugins available?

FYI: ROS2 Foxy, Gazebo 11

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2021-04-27 09:01:51 -0500

user300 gravatar image

The queue argument in the create_subscription() needs to be of type rclcpp::SensorDataQoS(). The following works:

ray_sub = this->create_subscription<sensor_msgs::msg::range>( "ray/range", rclcpp::SensorDataQoS(), std::bind(&DVL::setRayData, this, std::placeholders::_1));

edit flag offensive delete link more

Comments

this was really helpful. thanks

rosnroll gravatar image rosnroll  ( 2021-08-11 05:13:39 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2021-04-26 12:24:01 -0500

Seen: 738 times

Last updated: Apr 27 '21