Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Ensure latched messages are updated on every split #2261

Open
wants to merge 2 commits into
base: noetic-devel
Choose a base branch
from

Conversation

ggorjup
Copy link

@ggorjup ggorjup commented Jul 29, 2022

Summary

This fixes an issue with #1850 - latched messages from the same publisher are not updated in the Recorder.

Steps to Reproduce

  1. Create and run a node that periodically publishes latched messages, for example:
#!/usr/bin/env python3
import rospy
from std_msgs.msg import String

pub = rospy.Publisher('chatter', String, latch=True)
rospy.init_node('talker')
for i in range(20):
    pub.publish(str(i))
    rospy.sleep(5)
  1. Record the latched topic in splits:
    rosrun rosbag record -a --repeat-latched --duration 10 --split
  2. Check messages on the target topic in the last split:
    rostopic echo -b <last_split>.bag chatter

Expected behavior

The first message in the last split is the value of the latched topic when the split was started (e.g., data: "18").

Actual behavior

The first message in the last split is the value of the latched topic when the rosbag record was run (e.g., data: "0").

Implications

This behavior causes issues when recording latched topics that are not often updated. If the rosbag record is a long-running process, the latched topic values in some splits may be several hours old (if the publisher does not send an update within the split time frame).

Cause

Latched messages are stored as a std::map<std::pair<std::string, std::string>, OutgoingMessage>, where the key is a pair of strings (topic and publisher name) and the value is the latched message.

When updating the latched_msgs_ map, the std::map::insert() function is used. This behaves as expected when the key does not yet exist in the map. However, if the key exists, the old value is not updated:

Because element keys in a map are unique, the insertion operation checks whether each inserted element has a key equivalent to the one of an element already in the container, and if so, the element is not inserted, returning an iterator to this existing element

-- std::map::insert

This effectively means that the first value (latched message) that was inserted into the map will persist across the whole rosbag record.

Solution

Check for insertion success and assign value manually if required (see commit).

@ghost
Copy link

ghost commented Apr 27, 2023

I am running into issues caused by this, which strongly limits the viability of --repeat-latched.

@mjcarroll
Would it be possible to have a look at merging this bugfix?

Copy link

@AndreasNagel AndreasNagel left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested a change, but even without it, merging what is here is better than keeping a broken implementation around.

@kaarelvark
Copy link

Behavior has changed after #2351
Previously latched topics were repeated in the beginning of the bag without being latched.
Now those topics are latched, but they behave just as you described: first message is always the same in all split bags..

@nicolas-cadart
Copy link

What's the status of this fix? We are still experiencing this issue on ROS noetic, which is a major problem for checking the real state of long term topics in splitted bags...

@ggorjup
Copy link
Author

ggorjup commented Dec 20, 2024

@nicolas-cadart the fix is ready, just needs to be merged.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

4 participants