From bc1884d4f61832d332baf25421d903360163c731 Mon Sep 17 00:00:00 2001 From: Patrick Roncagliolo Date: Thu, 13 Jul 2023 19:08:03 +0200 Subject: [PATCH] Param parsing fixes --- rosbag2_transport/src/rosbag2_transport/player.cpp | 12 +++++++----- 1 file changed, 7 insertions(+), 5 deletions(-) diff --git a/rosbag2_transport/src/rosbag2_transport/player.cpp b/rosbag2_transport/src/rosbag2_transport/player.cpp index 54547a5b21..fc34e7cb94 100644 --- a/rosbag2_transport/src/rosbag2_transport/player.cpp +++ b/rosbag2_transport/src/rosbag2_transport/player.cpp @@ -94,14 +94,16 @@ Player::Player(const std::string & node_name, const rclcpp::NodeOptions & node_o { rosbag2_storage::StorageOptions storage_options; rosbag2_transport::PlayOptions play_options; - + + const std::vector empty_str_list; + // TODO check if positive auto read_ahead_queue_size_ = declare_parameter("play.read_ahead_queue_size", 1000); play_options.read_ahead_queue_size = static_cast(read_ahead_queue_size_); play_options.node_prefix = declare_parameter("play.node_prefix", ""); play_options.rate = declare_parameter("play.rate", 1.0); - play_options.topics_to_filter = declare_parameter>("play.topics_to_filter", {}); + play_options.topics_to_filter = declare_parameter>("play.topics_to_filter", empty_str_list); play_options.topics_regex_to_filter = declare_parameter("play.topics_regex_to_filter",""); play_options.topics_regex_to_exclude = declare_parameter("play.topics_regex_to_exclude",""); @@ -111,14 +113,14 @@ Player::Player(const std::string & node_name, const rclcpp::NodeOptions & node_o play_options.loop = declare_parameter("play.loop", false); // Use classic CLI/launchfile remap instead - // play_options.topic_remapping_options = declare_parameter>("play.topic_remapping_options", {}); + // play_options.topic_remapping_options = declare_parameter>("play.topic_remapping_options", empty_str_list); play_options.clock_publish_frequency = declare_parameter("play.clock_publish_frequency", 0.0); play_options.clock_publish_on_topic_publish = declare_parameter("play.clock_publish_on_topic_publish", false); - play_options.clock_trigger_topics = declare_parameter>("play.clock_trigger_topics", {}); + play_options.clock_trigger_topics = declare_parameter>("play.clock_trigger_topics", empty_str_list); auto playback_duration_ = declare_parameter("play.playback_duration", -1); - play_options.playback_duration = rclcpp::Duration::from_seconds(seconds); + play_options.playback_duration = rclcpp::Duration::from_seconds(playback_duration_); play_options.playback_until_timestamp = declare_parameter("play.playback_until_timestamp", -1); play_options.start_paused = declare_parameter("play.start_paused", false);