From eb06a3ab304261cc7eb7636e85ca017ebba50546 Mon Sep 17 00:00:00 2001 From: Martin Idel Date: Mon, 26 Nov 2018 11:43:30 +0100 Subject: [PATCH] GH-27 Provide polling frequency as option - make option available in RecordOptions - set to 100ms for now --- .../include/rosbag2_transport/record_options.hpp | 2 ++ rosbag2_transport/src/rosbag2_transport/recorder.cpp | 10 ++++++---- rosbag2_transport/src/rosbag2_transport/recorder.hpp | 3 ++- .../src/rosbag2_transport/rosbag2_transport_python.cpp | 2 ++ .../test/rosbag2_transport/test_record.cpp | 2 +- .../test/rosbag2_transport/test_record_all.cpp | 2 +- 6 files changed, 14 insertions(+), 7 deletions(-) diff --git a/rosbag2_transport/include/rosbag2_transport/record_options.hpp b/rosbag2_transport/include/rosbag2_transport/record_options.hpp index ebb4154bfd..9d4a3d7428 100644 --- a/rosbag2_transport/include/rosbag2_transport/record_options.hpp +++ b/rosbag2_transport/include/rosbag2_transport/record_options.hpp @@ -15,6 +15,7 @@ #ifndef ROSBAG2_TRANSPORT__RECORD_OPTIONS_HPP_ #define ROSBAG2_TRANSPORT__RECORD_OPTIONS_HPP_ +#include #include #include @@ -26,6 +27,7 @@ struct RecordOptions bool all; std::vector topics; std::string rmw_serialization_format; + std::chrono::milliseconds topic_polling_frequency; }; } // namespace rosbag2_transport diff --git a/rosbag2_transport/src/rosbag2_transport/recorder.cpp b/rosbag2_transport/src/rosbag2_transport/recorder.cpp index 4107503f28..c9928d11e8 100644 --- a/rosbag2_transport/src/rosbag2_transport/recorder.cpp +++ b/rosbag2_transport/src/rosbag2_transport/recorder.cpp @@ -34,7 +34,8 @@ Recorder::Recorder(std::shared_ptr writer, std::shared_ptr Recorder::launch_topics_discovery(std::vector topics) +std::future Recorder::launch_topics_discovery( + std::chrono::milliseconds topic_polling_frequency, std::vector topics) { - auto subscribe_to_topics = [this, topics] { + auto subscribe_to_topics = [this, topics, topic_polling_frequency] { while (rclcpp::ok()) { auto all_topics_and_types = topics.empty() ? node_->get_all_topics_with_types() : @@ -91,7 +93,7 @@ std::future Recorder::launch_topics_discovery(std::vector top } } } - std::this_thread::sleep_for(std::chrono::milliseconds(100)); + std::this_thread::sleep_for(topic_polling_frequency); } }; diff --git a/rosbag2_transport/src/rosbag2_transport/recorder.hpp b/rosbag2_transport/src/rosbag2_transport/recorder.hpp index 3cfb8fe5de..5c0a1ab3b5 100644 --- a/rosbag2_transport/src/rosbag2_transport/recorder.hpp +++ b/rosbag2_transport/src/rosbag2_transport/recorder.hpp @@ -43,7 +43,8 @@ class Recorder private: std::shared_ptr create_subscription( const std::string & topic_name, const std::string & topic_type); - std::future launch_topics_discovery(std::vector topics = {}); + std::future launch_topics_discovery( + std::chrono::milliseconds topic_polling_frequency, std::vector topics = {}); std::shared_ptr writer_; std::shared_ptr node_; diff --git a/rosbag2_transport/src/rosbag2_transport/rosbag2_transport_python.cpp b/rosbag2_transport/src/rosbag2_transport/rosbag2_transport_python.cpp index 05c6b1ab2d..661113ad45 100644 --- a/rosbag2_transport/src/rosbag2_transport/rosbag2_transport_python.cpp +++ b/rosbag2_transport/src/rosbag2_transport/rosbag2_transport_python.cpp @@ -13,6 +13,7 @@ // limitations under the License. #include +#include #include #include @@ -48,6 +49,7 @@ rosbag2_transport_record(PyObject * Py_UNUSED(self), PyObject * args, PyObject * storage_options.uri = std::string(uri); storage_options.storage_id = std::string(storage_id); record_options.all = all; + record_options.topic_polling_frequency = std::chrono::milliseconds(100); if (topics) { PyObject * topic_iterator = PyObject_GetIter(topics); diff --git a/rosbag2_transport/test/rosbag2_transport/test_record.cpp b/rosbag2_transport/test/rosbag2_transport/test_record.cpp index 5157533990..cad03c8f30 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_record.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_record.cpp @@ -37,7 +37,7 @@ TEST_F(RecordIntegrationTestFixture, published_messages_from_multiple_topics_are string_message->string_value = "Hello World"; std::string string_topic = "/string_topic"; - start_recording({false, {string_topic, array_topic}}); + start_recording({false, {string_topic, array_topic}, 100ms}); pub_man_.add_publisher( string_topic, string_message, 2); diff --git a/rosbag2_transport/test/rosbag2_transport/test_record_all.cpp b/rosbag2_transport/test/rosbag2_transport/test_record_all.cpp index 743d4ef356..b9aaf7fa83 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_record_all.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_record_all.cpp @@ -40,7 +40,7 @@ TEST_F(RecordIntegrationTestFixture, published_messages_from_multiple_topics_are pub_man_.add_publisher(string_topic, string_message, 2); pub_man_.add_publisher(array_topic, array_message, 2); - start_recording({true, {}, ""}); + start_recording({true, {}, "", 100ms}); run_publishers(); stop_recording();