rosbag2
rosbag2 copied to clipboard
Mixed-QoS settings used for ros2 bag play
Documenting the following issue to get feedback and understand if it is worth addressing or if the case is so infrequent that a change like this is not worth considering...
Description
When recording, ros2 bag record saves QoS information for each publisher on a specific topic to the database (under 'offered_qos_profiles'). Each message received on that topic is also saved. However, there is not an association between the messages and the QoS settings used to originally publish the messages. Currently, when playing back from a previously-recorded database, ros2 bag play creates a publisher for each topic (even if there were originally multiple publishers for that topic). When creating the publisher, it needs to provide a QoS profile. If the topic had a single publisher, or if a topic had multiple publishers but they all used the same QoS profile, there is not a problem figuring out the QoS profile to use. However, if the original publishers used different QoS profiles, ros2 bag play needs to adapt the recorded QoS profiles ("offered_qos_profiles") into one it can use for the publisher. In this case, the rosbag2 code uses a default QoS setting:
Rosbag2QoS Rosbag2QoS::adapt_offer_to_recorded_offers(
const std::string & topic_name, const std::vector<Rosbag2QoS> & profiles)
{
if (profiles.empty()) {
return Rosbag2QoS{};
}
if (all_profiles_effectively_same(profiles)) {
auto result = profiles[0];
return result.default_history();
}
ROSBAG2_TRANSPORT_LOG_WARN_STREAM(
"Not all original publishers on topic " << topic_name << " offered the same QoS profiles. "
"Rosbag2 cannot yet choose an adapted profile to offer for this mixed case. "
"Falling back to the rosbag2_transport default publisher offer.");
return Rosbag2QoS{};
}
The result is that "ros2 bag play" is not quite faithful, from a QoS perspective to the original publishing.
Implementation Notes / Suggestions
To implement this case, we would need to know the QoS settings used for each published message. We currently store the QoS profiles, but they are not associated with individual messages, but are only associated to a topic (which could possibly have multiple publishers with different QoS). It may be that this is a rare situation and publishers of the same topic should be using the same QoS settings.