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

Get message published before subscriber start

asked 2021-08-03 11:44:12 -0500

PatoInso gravatar image

Hello,

I have a publisher node set to publish only once a message right after it started. I have a subscriber node that subscribes to this topic but that is sometimes started a little time after the publisher (so its message is published before the subscriber has started)

How can the subscriber retrieve this message published before it started ?

I feel this may be done with QoS policies. I created the subscription with a QoS History depth of 10 (according to the documentation), but this message is not retrieved (but QoS policies are at least compatible since if a republish regularly the message after the subscriber started I receive it):

m_subMap = this->create_subscription<nav_msgs::msg::OccupancyGrid>("/map", 10, std::bind(&MapDataCallback, this, _1));
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2021-08-03 18:10:17 -0500

shonigmann gravatar image

You're right to look into QoS, but I think the setting you will want to look at is transient local (aka latching)

edit flag offensive delete link more

Comments

1

"latching" was indeed what I was looking for, thanks. This code works, by setting bith the subscriber and the publisher to durability "transient local" (in a way insopired from the slam_toolbox code):

/* Publiher side */
m_mapPublisher = this->create_publisher<nav_msgs::msg::OccupancyGrid>(
"/map", rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable());

/* Subscriber side */
rclcpp::QoS qosLatching = rclcpp::QoS(rclcpp::KeepLast(1));
qosLatching.transient_local();
qosLatching.reliable();
m_subMap = this->create_subscription<nav_msgs::msg::OccupancyGrid>("/map", qosLatching, std::bind(&MapDataCallback, this, _1));
PatoInso gravatar image PatoInso  ( 2021-08-04 09:55:04 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2021-08-03 11:44:12 -0500

Seen: 394 times

Last updated: Aug 03 '21