diff --git a/rosbag2_transport/src/rosbag2_transport/config_options_from_node_params.cpp b/rosbag2_transport/src/rosbag2_transport/config_options_from_node_params.cpp index 20fd9c292f..a7e55419a3 100644 --- a/rosbag2_transport/src/rosbag2_transport/config_options_from_node_params.cpp +++ b/rosbag2_transport/src/rosbag2_transport/config_options_from_node_params.cpp @@ -298,9 +298,7 @@ RecordOptions get_record_options_from_node_params(rclcpp::Node * node) "start_paused", false); - record_options.use_sim_time = node->declare_parameter( - "use_sim_time", - false); + record_options.use_sim_time = node->get_parameter("use_sim_time").get_value(); if (record_options.use_sim_time && record_options.is_discovery_disabled) { diff --git a/rosbag2_transport/test/resources/params_recorder.yaml b/rosbag2_transport/test/resources/params_recorder.yaml index 9f4676b812..4bb5412683 100644 --- a/rosbag2_transport/test/resources/params_recorder.yaml +++ b/rosbag2_transport/test/resources/params_recorder.yaml @@ -2,7 +2,7 @@ recorder_params_node: ros__parameters: all: true is_discovery_disabled: true - topics: {"topic", "other_topic"} + topics: ["topic", "other_topic"] rmw_serialization_format: "cdr" topic_polling_interval: sec: 0 diff --git a/rosbag2_transport/test/rosbag2_transport/rosbag2_record_test_fixture.hpp b/rosbag2_transport/test/rosbag2_transport/rosbag2_record_test_fixture.hpp new file mode 100644 index 0000000000..65f933099e --- /dev/null +++ b/rosbag2_transport/test/rosbag2_transport/rosbag2_record_test_fixture.hpp @@ -0,0 +1,41 @@ +// Copyright 2018, Patrick Roncagliolo +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef ROSBAG2_TRANSPORT__ROSBAG2_RECORD_TEST_FIXTURE_HPP_ +#define ROSBAG2_TRANSPORT__ROSBAG2_RECORD_TEST_FIXTURE_HPP_ + +#include + +#include "rosbag2_test_common/publication_manager.hpp" +#include "rosbag2_transport_test_fixture.hpp" + +class RosBag2RecordTestFixture : public Rosbag2TransportTestFixture +{ +public: + RosBag2RecordTestFixture() + : Rosbag2TransportTestFixture() + { + rclcpp::init(0, nullptr); + pub_ = std::make_shared(); + } + + ~RosBag2RecordTestFixture() override + { + rclcpp::shutdown(); + } + + std::shared_ptr pub_; +}; + +#endif // ROSBAG2_TRANSPORT__ROSBAG2_RECORD_TEST_FIXTURE_HPP_ diff --git a/rosbag2_transport/test/rosbag2_transport/test_play_params.cpp b/rosbag2_transport/test/rosbag2_transport/test_play_params.cpp index e4385d7bb0..8ecc7c84c4 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_play_params.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_play_params.cpp @@ -50,12 +50,12 @@ TEST_F(RosBag2PlayTestFixture, parse_parameter_from_file) { YAML::Node yaml_storage_opt = YAML::convert().encode( storage_options); - auto param_node = YAML::LoadFile(_SRC_RESOURCES_DIR_PATH "/params.yaml"); + auto param_node = YAML::LoadFile(_SRC_RESOURCES_DIR_PATH "/params_player.yaml"); auto qos_node = YAML::LoadFile(_SRC_RESOURCES_DIR_PATH "/overrides.yaml"); YAML::Emitter emitter; emitter - << YAML::Newline << YAML::Comment("params.yaml") + << YAML::Newline << YAML::Comment("params_player.yaml") << param_node << YAML::Newline << YAML::Newline << YAML::Comment("overrides.yaml") << qos_node << YAML::Newline diff --git a/rosbag2_transport/test/rosbag2_transport/test_record_params.cpp b/rosbag2_transport/test/rosbag2_transport/test_record_params.cpp index 016e99e8c5..22f851139f 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_record_params.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_record_params.cpp @@ -24,11 +24,11 @@ #include "rclcpp/rclcpp.hpp" #include "mock_recorder.hpp" -#include "rosbag2_transport_test_fixture.hpp" +#include "rosbag2_record_test_fixture.hpp" #include "rosbag2_storage/storage_options.hpp" #include "rosbag2_transport/record_options.hpp" -TEST_F(Rosbag2TransportTestFixture, parse_parameter_from_file) { +TEST_F(RosBag2RecordTestFixture, parse_parameter_from_file) { // _SRC_RESOURCES_DIR_PATH defined in CMakeLists.txt rclcpp::NodeOptions opts; opts.arguments( @@ -50,12 +50,15 @@ TEST_F(Rosbag2TransportTestFixture, parse_parameter_from_file) { YAML::Node yaml_storage_opt = YAML::convert().encode( storage_options); - auto param_node = YAML::LoadFile(_SRC_RESOURCES_DIR_PATH "/params.yaml"); + auto param_node = YAML::LoadFile(_SRC_RESOURCES_DIR_PATH "/params_recorder.yaml"); + auto qos_node = YAML::LoadFile(_SRC_RESOURCES_DIR_PATH "/overrides.yaml"); YAML::Emitter emitter; emitter << YAML::Newline << YAML::Comment("params.yaml") << param_node << YAML::Newline + << YAML::Newline << YAML::Comment("overrides.yaml") + << qos_node << YAML::Newline << YAML::Newline << YAML::Comment("node record parameters") << yaml_record_opt << YAML::Newline << YAML::Newline << YAML::Comment("node storage parameters")