Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add blacklisted topics #1

Merged
merged 2 commits into from
Aug 31, 2022
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 2 additions & 0 deletions rosbag2_snapshot/include/rosbag2_snapshot/snapshotter.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -131,6 +131,8 @@ struct SnapshotterOptions
// Provides list of topics to snapshot and their limit configurations
topics_t topics_;

topics_t blacklist_topics_;

SnapshotterOptions(
rclcpp::Duration default_duration_limit = rclcpp::Duration(30s),
int32_t default_memory_limit = -1);
Expand Down
28 changes: 22 additions & 6 deletions rosbag2_snapshot/src/snapshotter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -85,6 +85,8 @@ bool SnapshotterOptions::addTopic(
rclcpp::Duration duration,
int32_t memory)
{
if(blacklist_topics_.find(topic_details) != blacklist_topics_.end()) return false;

SnapshotterTopicOptions ops(duration, memory);
std::pair<topics_t::iterator, bool> ret;
ret = topics_.emplace(topic_details, ops);
Expand Down Expand Up @@ -287,6 +289,7 @@ Snapshotter::~Snapshotter()
void Snapshotter::parseOptionsFromParams()
{
std::vector<std::string> topics{};
bool is_blacklist = true;

try {
options_.default_duration_limit_ = rclcpp::Duration::from_seconds(
Expand Down Expand Up @@ -319,8 +322,18 @@ void Snapshotter::parseOptionsFromParams()
}
}

try {
is_blacklist = declare_parameter<bool>(
"is_blacklist", true);
} catch (const rclcpp::ParameterTypeException & ex) {
if (std::string{ex.what()}.find("not set") == std::string::npos) {
RCLCPP_ERROR(get_logger(), "is_blacklist must be a bool.");
throw ex;
}
}

if (topics.size() > 0) {
options_.all_topics_ = false;
options_.all_topics_ = is_blacklist ? true : false;

for (const auto & topic : topics) {
std::string prefix = "topic_details." + topic;
Expand Down Expand Up @@ -364,9 +377,10 @@ void Snapshotter::parseOptionsFromParams()
TopicDetails dets{};
dets.name = topic;
dets.type = topic_type;

if(is_blacklist) options_.blacklist_topics_.insert(SnapshotterOptions::topics_t::value_type(dets, opts));
else options_.topics_.insert(SnapshotterOptions::topics_t::value_type(dets, opts));

options_.topics_.insert(
SnapshotterOptions::topics_t::value_type(dets, opts));
}
} else {
options_.all_topics_ = true;
Expand Down Expand Up @@ -433,10 +447,12 @@ void Snapshotter::subscribe(
opts.topic_stats_options.state = rclcpp::TopicStatisticsState::Enable;
opts.topic_stats_options.publish_topic = topic_details.name + "/statistics";

bool is_image = topic_details.type == "sensor_msgs/msg/Image";

auto sub = create_generic_subscription(
topic_details.name,
topic_details.type,
rclcpp::QoS{10},
is_image ? rclcpp::SensorDataQoS() : rclcpp::QoS{10},
std::bind(&Snapshotter::topicCb, this, _1, queue),
opts
);
Expand Down Expand Up @@ -643,8 +659,8 @@ void Snapshotter::pollTopics()
}

if (name_type.second.size() > 1) {
RCLCPP_ERROR(get_logger(), "Subscribed topic has more than one associated type.");
return;
RCLCPP_INFO_STREAM_ONCE(get_logger(), "Subscribed topic has more than one associated type " << name_type.first );
continue;
}

TopicDetails details{};
Expand Down