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
Open
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 5 additions & 1 deletion tools/rosbag/src/recorder.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -347,7 +347,11 @@ void Recorder::doQueue(const ros::MessageEvent<topic_tools::ShapeShifter const>&
ros::M_string::const_iterator it2 = out.connection_header->find("callerid");
if (it2 != out.connection_header->end())
{
latched_msgs_.insert({{subscriber->getTopic(), it2->second}, out});
auto const result = latched_msgs_.insert({{subscriber->getTopic(), it2->second}, out});

Choose a reason for hiding this comment

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

Suggested change
auto const result = latched_msgs_.insert({{subscriber->getTopic(), it2->second}, out});
latched_msgs_[{subscriber->getTopic(), it2->second}] = out;

Choose a reason for hiding this comment

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

The [] operator does exactly what's expected here, in case the key doesn't exist in the map, it will be created and when it does exist, it will be updated.

Copy link
Author

Choose a reason for hiding this comment

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

Thanks for the suggestion - the [] operator is indeed cleaner since it removes the need for the extra manual check (in lines 351-354).

I'll try to update it shortly (I don't have the test environment handy anymore).

Copy link
Author

Choose a reason for hiding this comment

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

@AndreasNagel I tried your suggestion and unfortunately it fails to build:
error: no matching function for call to ‘rosbag::OutgoingMessage::OutgoingMessage()’

I believe this is due to the behavior of the [] operator when a key is not found in the map. From the docs:

If k does not match the key of any element in the container, the function inserts a new element with that key and returns a reference to its mapped value.

When a key is missing, the [] operator tries to create an OutgoingMessage object with an empty constructor that does not exist: OutgoingMessage(). (The object seems to only have one constructor that requires 4 arguments.)

I didn't find an easy way to go around this without creating an empty constructor for OutgoingMessage - I'd prefer to avoid introducing a change like that.

Choose a reason for hiding this comment

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

Good point, I missed that OutgoingMessage doesn't have a default constructor. I agree, there's no point in creating one just to use the [] operator. There's insert_or_assign in c++17, but nothing with equivalent functionality in c++14, so what you have there is probably as good as it gets. Still hoping, that this change will get merged one day.

if (not result.second) // The map::insert function does not update values of existing keys
{
result.first->second = out;
}
}
}
}
Expand Down