Skip to content

Commit

Permalink
Reduce message spam when topics to be recorded do not exist (#1018)
Browse files Browse the repository at this point in the history
* move topic_filter.hpp to expose to recorder.hpp

Signed-off-by: Brian Chen <brian.chen@openrobotics.org>

* fix #1011: persist TopicFilter to avoid warning spam

Signed-off-by: Brian Chen <brian.chen@openrobotics.org>

* address pr comments

Signed-off-by: Brian Chen <brian.chen@openrobotics.org>
  • Loading branch information
ihasdapie authored May 25, 2022
1 parent ffd56e0 commit d97e291
Show file tree
Hide file tree
Showing 6 changed files with 8 additions and 6 deletions.
2 changes: 2 additions & 0 deletions rosbag2_transport/include/rosbag2_transport/recorder.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,7 @@

#include "rosbag2_transport/record_options.hpp"
#include "rosbag2_transport/visibility_control.hpp"
#include "rosbag2_transport/topic_filter.hpp"

namespace rosbag2_cpp
{
Expand Down Expand Up @@ -143,6 +144,7 @@ class Recorder : public rclcpp::Node

void warn_if_new_qos_for_subscribed_topic(const std::string & topic_name);

std::unique_ptr<TopicFilter> topic_filter_;
std::shared_ptr<rosbag2_cpp::Writer> writer_;
rosbag2_storage::StorageOptions storage_options_;
rosbag2_transport::RecordOptions record_options_;
Expand Down
2 changes: 1 addition & 1 deletion rosbag2_transport/src/rosbag2_transport/bag_rewrite.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@
#include "rosbag2_transport/reader_writer_factory.hpp"

#include "logging.hpp"
#include "topic_filter.hpp"
#include "rosbag2_transport/topic_filter.hpp"

namespace
{
Expand Down
6 changes: 3 additions & 3 deletions rosbag2_transport/src/rosbag2_transport/recorder.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@
#include "rosbag2_storage/yaml.hpp"
#include "rosbag2_transport/qos.hpp"

#include "topic_filter.hpp"
#include "rosbag2_transport/topic_filter.hpp"

namespace rosbag2_transport
{
Expand Down Expand Up @@ -88,6 +88,7 @@ Recorder::Recorder(
[this](KeyboardHandler::KeyCode /*key_code*/,
KeyboardHandler::KeyModifiers /*key_modifiers*/) {this->toggle_paused();},
Recorder::kPauseResumeToggleKey);
topic_filter_ = std::make_unique<TopicFilter>(record_options, this->get_node_graph_interface());
// show instructions
RCLCPP_INFO_STREAM(
get_logger(),
Expand Down Expand Up @@ -199,8 +200,7 @@ std::unordered_map<std::string, std::string>
Recorder::get_requested_or_available_topics()
{
auto all_topics_and_types = this->get_topic_names_and_types();
TopicFilter topic_filter{record_options_, this->get_node_graph_interface()};
return topic_filter.filter_topics(all_topics_and_types);
return topic_filter_->filter_topics(all_topics_and_types);
}

std::unordered_map<std::string, std::string>
Expand Down
2 changes: 1 addition & 1 deletion rosbag2_transport/src/rosbag2_transport/topic_filter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
#include "rosbag2_cpp/typesupport_helpers.hpp"

#include "logging.hpp"
#include "topic_filter.hpp"
#include "rosbag2_transport/topic_filter.hpp"

namespace
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
#include <unordered_set>
#include <vector>

#include "./topic_filter.hpp"
#include "rosbag2_transport/topic_filter.hpp"

using namespace ::testing; // NOLINT

Expand Down

0 comments on commit d97e291

Please sign in to comment.