From b8c34c31a09b31f2d43f0fa68a536ef79f9991d6 Mon Sep 17 00:00:00 2001 From: Anish_deva <51463994+adev4a@users.noreply.github.com> Date: Fri, 1 Nov 2024 13:28:11 -0400 Subject: [PATCH] Arc 231 fix ros2 bag record (#2453) * set shell false * add subscriber qos transient local topics * add topic profile overrides --- carma/config/rosbag2_qos_overrides.yaml | 31 +++++++++++++++++++++++++ carma/launch/ros2_rosbag.launch.py | 5 +++- 2 files changed, 35 insertions(+), 1 deletion(-) diff --git a/carma/config/rosbag2_qos_overrides.yaml b/carma/config/rosbag2_qos_overrides.yaml index fd41b43142..1616bc7793 100644 --- a/carma/config/rosbag2_qos_overrides.yaml +++ b/carma/config/rosbag2_qos_overrides.yaml @@ -1,7 +1,38 @@ ## This file defines Quality of Service settings for subscribers created in rosbag2 recording. ## Topics defined here have multiple publishers with different QoS settings which may lead to the rosbag ignoring messages. ## The QoS settings defined here give the subscriber less restrictive settings, so all messages from the topic are retained. + /rosout: history: keep_all reliability: reliable durability: volatile + +/environment/lanelet2_map_viz: + history: keep_last + reliability: reliable + durability: transient_local + depth: 1 + +/environment/lanelet_map_bin: + history: keep_last + reliability: reliable + durability: transient_local + depth: 1 + +/localization/map_param_loader/georeference: + history: keep_last + reliability: reliable + durability: transient_local + depth: 1 + +/localization/points_map: + history: keep_last + reliability: reliable + durability: transient_local + depth: 1 + +/message/incoming_geofence_control: + history: keep_last + reliability: reliable + durability: transient_local + depth: 1 \ No newline at end of file diff --git a/carma/launch/ros2_rosbag.launch.py b/carma/launch/ros2_rosbag.launch.py index 1a638e9ad5..2ab9dc23af 100644 --- a/carma/launch/ros2_rosbag.launch.py +++ b/carma/launch/ros2_rosbag.launch.py @@ -65,7 +65,10 @@ def record_ros2_rosbag(context: LaunchContext, vehicle_config_param_file, rosbag exclude_topics_regex += str(topic) + "|" proc = ExecuteProcess( - cmd=['ros2', 'bag', 'record', '-s', 'mcap', '--qos-profile-overrides-path', overriding_qos_profiles, '-o', '/opt/carma/logs/rosbag2_' + str(datetime.now().strftime('%Y-%m-%d_%H%M%S')), '-a', '-x', exclude_topics_regex], + cmd=['ros2', 'bag', 'record', '-a', '-s', 'mcap', + '--qos-profile-overrides-path', overriding_qos_profiles, + '-o', '/opt/carma/logs/rosbag2_' + str(datetime.now().strftime('%Y-%m-%d_%H%M%S')), + '-x', exclude_topics_regex], output='screen', shell='true' )