Skip to content

Commit

Permalink
Resolve the conflicts caused by the rebase
Browse files Browse the repository at this point in the history
Signed-off-by: Barry Xu <barry.xu@sony.com>
  • Loading branch information
Barry-Xu-2018 committed Dec 22, 2023
1 parent 7886bf1 commit 8351852
Show file tree
Hide file tree
Showing 6 changed files with 25 additions and 14 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -131,10 +131,14 @@ PlayOptions get_play_options_from_node_params(rclcpp::Node & node)

play_options.topics_to_filter = node.declare_parameter<std::vector<std::string>>(
"play.topics_to_filter", std::vector<std::string>());
play_options.services_to_filter = node.declare_parameter<std::vector<std::string>>(
"play.services_to_filter", std::vector<std::string>());

play_options.topics_regex_to_filter =
node.declare_parameter<std::string>("play.topics_regex_to_filter", "");
play_options.regex_to_filter =
node.declare_parameter<std::string>("play.regex_to_filter", "");

play_options.services_regex_to_exclude =
node.declare_parameter<std::string>("play.services_regex_to_exclude", "");
play_options.topics_regex_to_exclude =
node.declare_parameter<std::string>("play.topics_regex_to_exclude", "");

Expand Down
10 changes: 8 additions & 2 deletions rosbag2_transport/src/rosbag2_transport/play_options.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,8 +31,10 @@ Node convert<rosbag2_transport::PlayOptions>::encode(
node["node_prefix"] = play_options.node_prefix;
node["rate"] = play_options.rate;
node["topics_to_filter"] = play_options.topics_to_filter;
node["topics_regex_to_filter"] = play_options.topics_regex_to_filter;
node["services_to_filter"] = play_options.services_to_filter;
node["regex_to_filter"] = play_options.regex_to_filter;
node["topics_regex_to_exclude"] = play_options.topics_regex_to_exclude;
node["services_regex_to_exclude"] = play_options.services_regex_to_exclude;
node["topic_qos_profile_overrides"] =
YAML::convert<std::unordered_map<std::string, rclcpp::QoS>>::encode(
play_options.topic_qos_profile_overrides);
Expand Down Expand Up @@ -67,9 +69,13 @@ bool convert<rosbag2_transport::PlayOptions>::decode(
optional_assign<float>(node, "rate", play_options.rate);
optional_assign<std::vector<std::string>>(
node, "topics_to_filter", play_options.topics_to_filter);
optional_assign<std::string>(node, "topics_regex_to_filter", play_options.topics_regex_to_filter);
optional_assign<std::vector<std::string>>(
node, "services_to_filter", play_options.services_to_filter);
optional_assign<std::string>(node, "regex_to_filter", play_options.regex_to_filter);
optional_assign<std::string>(
node, "topics_regex_to_exclude", play_options.topics_regex_to_exclude);
optional_assign<std::string>(
node, "services_regex_to_exclude", play_options.services_regex_to_exclude);

optional_assign<std::unordered_map<std::string, rclcpp::QoS>>(
node, "topic_qos_profile_overrides", play_options.topic_qos_profile_overrides);
Expand Down
10 changes: 4 additions & 6 deletions rosbag2_transport/src/rosbag2_transport/player.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -492,21 +492,19 @@ bool PlayerImpl::play()
try {
if (std::holds_alternative<SharedPlayerPublisher>(pub.second)) {
if (!std::get<SharedPlayerPublisher>(pub.second)
->generic_publisher()->wait_for_all_acked(timeout))
->generic_publisher()->wait_for_all_acked(timeout))
{
RCLCPP_ERROR(
owner_->get_logger(),
"Timed out while waiting for all published messages to be acknowledged for topic %s",
pub.first.c_str());
"Timed out while waiting for all published messages to be acknowledged for topic "
"%s", pub.first.c_str());
}
}
} catch (std::exception & e) {
RCLCPP_ERROR(
owner_->get_logger(),
"Exception occurred while waiting for all published messages to be acknowledged for "
"topic %s : %s",
pub.first.c_str(),
e.what());
"topic %s : %s", pub.first.c_str(), e.what());
}
}
}
Expand Down
4 changes: 3 additions & 1 deletion rosbag2_transport/test/resources/player_node_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -5,8 +5,10 @@ player_params_node:
node_prefix: "test"
rate: 13.0
topics_to_filter: ["/foo", "/bar"]
topics_regex_to_filter: "[xyz]/topic"
services_to_filter: ["/service1", "/service2"]
regex_to_filter: "[xyz]/topic_service"
topics_regex_to_exclude: "[abc]/topic"
services_regex_to_exclude: "[abc]/service"
loop: false
clock_publish_frequency: 19.0
clock_publish_on_topic_publish: true
Expand Down
2 changes: 0 additions & 2 deletions rosbag2_transport/test/rosbag2_transport/mock_player.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -68,8 +68,6 @@ class MockPlayer : public rosbag2_transport::Player
return cli_list;
}

using rosbag2_transport::Player::wait_for_playback_to_start;

size_t get_number_of_registered_pre_callbacks()
{
return get_number_of_registered_on_play_msg_pre_callbacks();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -138,8 +138,11 @@ TEST_P(ComposablePlayerTests, player_can_parse_parameters_from_file) {
EXPECT_EQ(play_options.rate, 13.0);
std::vector<std::string> topics_to_filter {"/foo", "/bar"};
EXPECT_EQ(play_options.topics_to_filter, topics_to_filter);
EXPECT_EQ(play_options.topics_regex_to_filter, "[xyz]/topic");
std::vector<std::string> services_to_filter {"/service1", "/service2"};
EXPECT_EQ(play_options.services_to_filter, services_to_filter);
EXPECT_EQ(play_options.regex_to_filter, "[xyz]/topic_service");
EXPECT_EQ(play_options.topics_regex_to_exclude, "[abc]/topic");
EXPECT_EQ(play_options.services_regex_to_exclude, "[abc]/service");
std::unordered_map<std::string, rclcpp::QoS> topic_qos_profile_overrides{
std::pair{
"/overrided_topic_qos",
Expand Down

0 comments on commit 8351852

Please sign in to comment.