-
Notifications
You must be signed in to change notification settings - Fork 305
Closed
Labels
bugSomething isn't workingSomething isn't working
Description
Description
Sometimes ros2 bag record erroneously reports a volatile publisher is discovered but rosbag is recording with transient-local QoS already.
Expected Behavior
No warning. The subscription taken by rosbag is volatile as it should be.
Actual Behavior
It reports this:
A new publisher for susbcribed topic /turtle1/cmd_vel was found offering RMW_QOS_POLICY_DURABILITY_VOLATILE, but rosbag2 already subscribed requesting RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL. Messages from this new publisher will not be recorded.
the subscription taken is actually volatile.
To Reproduce
ros2 ros2 run turtlesim turtle_teleop_keyros2 bag record /turtle1/cmd_vel
It doesn't always go wrong, it seems to be timing-dependent and require a release build.
System (please complete the following information)
- OS: Ubuntu 20.04
- ROS 2 Distro: what is about to be released as Galactic
- Version: source build using ros2/ros2@052d7c3
Additional context
A bit of digging suggests the problem is in rosbag2_transport/src/rosbag2_transport/recorder.cpp:
void Recorder::warn_if_new_qos_for_subscribed_topic(const std::string & topic_name)
{
auto existing_subscription = subscriptions_.find(topic_name);
if (existing_subscription == subscriptions_.end()) {
// Not subscribed yet
return;
}
if (topics_warned_about_incompatibility_.count(topic_name) > 0) {
// Already warned about this topic
return;
}
const auto & used_profile = existing_subscription->second->get_actual_qos().get_rmw_qos_profile();I think (but I am no C++ expert by any stretch of the imagination) that the temporary rclcpp::QoS object returned by get_actual_qos() is not kept alive long enough and that the memory pointed to by used_profile gets reused.
Reactions are currently unavailable
Metadata
Metadata
Assignees
Labels
bugSomething isn't workingSomething isn't working