Skip to content

Commit

Permalink
fix: use transient_local qos for route (#149)
Browse files Browse the repository at this point in the history
* fix: use transient_local qos for route

Signed-off-by: 1222-takeshi <m.takeshi1995@gmail.com>

* ci(pre-commit): autofix

Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com>
Co-authored-by: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com>
  • Loading branch information
4 people authored Jan 13, 2022
1 parent 3e27b12 commit 244268b
Show file tree
Hide file tree
Showing 3 changed files with 4 additions and 3 deletions.
3 changes: 2 additions & 1 deletion perception/traffic_light_map_based_detector/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -103,7 +103,8 @@ MapBasedDetector::MapBasedDetector(const rclcpp::NodeOptions & node_options)
"~/input/camera_info", rclcpp::SensorDataQoS(),
std::bind(&MapBasedDetector::cameraInfoCallback, this, _1));
route_sub_ = create_subscription<autoware_auto_planning_msgs::msg::HADMapRoute>(
"~/input/route", 1, std::bind(&MapBasedDetector::routeCallback, this, _1));
"~/input/route", rclcpp::QoS{1}.transient_local(),
std::bind(&MapBasedDetector::routeCallback, this, _1));

// publishers
roi_pub_ = this->create_publisher<autoware_auto_perception_msgs::msg::TrafficLightRoiArray>(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@ GoalPoseVisualizer::GoalPoseVisualizer(const rclcpp::NodeOptions & node_options)
: Node("goal_pose_visualizer_node", node_options)
{
sub_route_ = create_subscription<autoware_auto_planning_msgs::msg::HADMapRoute>(
"input/route", rclcpp::QoS{1},
"input/route", rclcpp::QoS{1}.transient_local(),
std::bind(&GoalPoseVisualizer::echoBackRouteCallback, this, std::placeholders::_1));
pub_goal_pose_ = create_publisher<geometry_msgs::msg::PoseStamped>(
"output/goal_pose", rclcpp::QoS{1}.transient_local());
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -346,7 +346,7 @@ ScenarioSelectorNode::ScenarioSelectorNode(const rclcpp::NodeOptions & node_opti
"input/lanelet_map", rclcpp::QoS{1}.transient_local(),
std::bind(&ScenarioSelectorNode::onMap, this, std::placeholders::_1));
sub_route_ = this->create_subscription<autoware_auto_planning_msgs::msg::HADMapRoute>(
"input/route", rclcpp::QoS{1},
"input/route", rclcpp::QoS{1}.transient_local(),
std::bind(&ScenarioSelectorNode::onRoute, this, std::placeholders::_1));
sub_odom_ = this->create_subscription<nav_msgs::msg::Odometry>(
"input/odometry", rclcpp::QoS{100},
Expand Down

0 comments on commit 244268b

Please sign in to comment.