From ec055cb7eb09fa1bbc97b3d12ebda9ce9537658a Mon Sep 17 00:00:00 2001 From: Daniel Dube Date: Mon, 6 May 2019 19:18:35 +0200 Subject: [PATCH] Fixed all linter errors. (Change Request #1) --- .../include/rosbag2_transport/play_options.hpp | 4 ++-- .../src/rosbag2_transport/player.cpp | 6 +++--- .../rosbag2_transport_python.cpp | 15 ++++++++------- 3 files changed, 13 insertions(+), 12 deletions(-) diff --git a/rosbag2_transport/include/rosbag2_transport/play_options.hpp b/rosbag2_transport/include/rosbag2_transport/play_options.hpp index 59726a0681..8c50809262 100644 --- a/rosbag2_transport/include/rosbag2_transport/play_options.hpp +++ b/rosbag2_transport/include/rosbag2_transport/play_options.hpp @@ -24,11 +24,11 @@ namespace rosbag2_transport struct PlayOptions { public: - using TopicFilter = std::function; + using TopicFilter = std::function; size_t read_ahead_queue_size; std::string node_prefix = ""; - TopicFilter topic_filter = [](const std::string&){return false;}; + TopicFilter topic_filter = [](const std::string &) {return false;}; }; } // namespace rosbag2_transport diff --git a/rosbag2_transport/src/rosbag2_transport/player.cpp b/rosbag2_transport/src/rosbag2_transport/player.cpp index e57c21ada0..64624140c5 100644 --- a/rosbag2_transport/src/rosbag2_transport/player.cpp +++ b/rosbag2_transport/src/rosbag2_transport/player.cpp @@ -130,8 +130,9 @@ void Player::play_messages_until_queue_empty(const PlayOptions & options) { ReplayableMessage message; while (message_queue_.try_dequeue(message) && rclcpp::ok()) { - if (options.topic_filter(message.message->topic_name)) + if (options.topic_filter(message.message->topic_name)) { continue; + } std::this_thread::sleep_until(start_time_ + message.time_since_start); if (rclcpp::ok()) { publishers_[message.message->topic_name]->publish(message.message->serialized_data); @@ -144,8 +145,7 @@ void Player::prepare_publishers(const PlayOptions & options) auto topics = reader_->get_all_topics_and_types(); for (const auto & topic : topics) { - if (options.topic_filter(topic.name)) - { + if (options.topic_filter(topic.name)) { ROSBAG2_TRANSPORT_LOG_INFO("Excluding topic %s", topic.name.c_str()); continue; } diff --git a/rosbag2_transport/src/rosbag2_transport/rosbag2_transport_python.cpp b/rosbag2_transport/src/rosbag2_transport/rosbag2_transport_python.cpp index 21b00752e1..09b3d9a091 100644 --- a/rosbag2_transport/src/rosbag2_transport/rosbag2_transport_python.cpp +++ b/rosbag2_transport/src/rosbag2_transport/rosbag2_transport_python.cpp @@ -142,13 +142,14 @@ rosbag2_transport_play(PyObject * Py_UNUSED(self), PyObject * args, PyObject * k } if (exclude_topics_list.empty() == false) { - auto topic_filter_function = [exclude_topics_list](const std::string& topic) - { - auto entry = exclude_topics_list.find(topic); - if (entry == exclude_topics_list.end()) - return false; - return true; - }; + auto topic_filter_function = [exclude_topics_list](const std::string & topic) + { + auto entry = exclude_topics_list.find(topic); + if (entry == exclude_topics_list.end()) { + return false; + } + return true; + }; play_options.topic_filter = topic_filter_function; }