diff --git a/tools/rosbag/src/recorder.cpp b/tools/rosbag/src/recorder.cpp index c3a3fa2f2f..15e7a9d2c1 100644 --- a/tools/rosbag/src/recorder.cpp +++ b/tools/rosbag/src/recorder.cpp @@ -347,7 +347,11 @@ void Recorder::doQueue(const ros::MessageEvent& 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}); + if (not result.second) // The map::insert function does not update values of existing keys + { + result.first->second = out; + } } } }