From bd48eef284c4e1ebd150deac9515a9bbfefe43aa Mon Sep 17 00:00:00 2001 From: nik-tier4 <71747268+nik-tier4@users.noreply.github.com> Date: Fri, 11 Dec 2020 16:17:03 +0900 Subject: [PATCH] fixing trasient_local in ROS2 packages (#160) --- .../ndt_scan_matcher/src/ndt_scan_matcher_core.cpp | 2 +- .../util/pose_initializer/src/pose_initializer_core.cpp | 2 +- .../src/lanelet2_map_loader/lanelet2_map_visualization.cpp | 2 +- map/map_tf_generator/nodes/map_tf_generator.cpp | 2 +- .../map_based_prediction/src/map_based_prediction_ros.cpp | 2 +- .../traffic_light_map_based_detector/src/node.cpp | 2 +- .../src/mission_planner_lanelet2/mission_planner_lanelet2.cpp | 2 +- .../behavior_planning/behavior_velocity_planner/src/node.cpp | 2 +- .../behavior_planning/lane_change_planner/src/lane_changer.cpp | 2 +- .../turn_signal_decider/src/turn_signal_decider_core.cpp | 2 +- .../nodes/costmap_generator/costmap_generator_node.cpp | 2 +- .../src/scenario_selector_node/scenario_selector_node.cpp | 2 +- 12 files changed, 12 insertions(+), 12 deletions(-) diff --git a/localization/pose_estimator/ndt_scan_matcher/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp b/localization/pose_estimator/ndt_scan_matcher/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp index 0aeb29f3cfd77..3ecc79927e220 100644 --- a/localization/pose_estimator/ndt_scan_matcher/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp +++ b/localization/pose_estimator/ndt_scan_matcher/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp @@ -101,7 +101,7 @@ NDTScanMatcher::NDTScanMatcher() "ekf_pose_with_covariance", 100, std::bind(&NDTScanMatcher::callbackInitialPose, this, std::placeholders::_1)); map_points_sub_ = this->create_subscription( - "pointcloud_map", 1, + "pointcloud_map", rclcpp::QoS{1}.transient_local(), std::bind(&NDTScanMatcher::callbackMapPoints, this, std::placeholders::_1)); sensor_points_sub_ = this->create_subscription( "points_raw", 1, std::bind(&NDTScanMatcher::callbackSensorPoints, this, std::placeholders::_1)); diff --git a/localization/util/pose_initializer/src/pose_initializer_core.cpp b/localization/util/pose_initializer/src/pose_initializer_core.cpp index 8b91b622e3e3f..9466b68adae0b 100644 --- a/localization/util/pose_initializer/src/pose_initializer_core.cpp +++ b/localization/util/pose_initializer/src/pose_initializer_core.cpp @@ -50,7 +50,7 @@ PoseInitializer::PoseInitializer() "initialpose", 10, std::bind(&PoseInitializer::callbackInitialPose, this, std::placeholders::_1)); map_points_sub_ = this->create_subscription( - "pointcloud_map", 1, + "pointcloud_map", rclcpp::QoS{1}.transient_local(), std::bind(&PoseInitializer::callbackMapPoints, this, std::placeholders::_1)); const bool use_first_gnss_topic = this->declare_parameter("use_first_gnss_topic", true); diff --git a/map/map_loader/src/lanelet2_map_loader/lanelet2_map_visualization.cpp b/map/map_loader/src/lanelet2_map_loader/lanelet2_map_visualization.cpp index 0e4ee529b9692..f083feeebe077 100644 --- a/map/map_loader/src/lanelet2_map_loader/lanelet2_map_visualization.cpp +++ b/map/map_loader/src/lanelet2_map_loader/lanelet2_map_visualization.cpp @@ -127,7 +127,7 @@ int main(int argc, char ** argv) rclcpp::init(argc, argv); auto node = rclcpp::Node::make_shared("lanelet2_map_visualizer"); auto bin_map_sub = node->create_subscription( - "input/lanelet2_map", rclcpp::QoS{1}, std::bind(&binMapCallback, std::placeholders::_1)); + "input/lanelet2_map", rclcpp::QoS{1}.transient_local(), std::bind(&binMapCallback, std::placeholders::_1)); rclcpp::QoS durable_qos{1}; durable_qos.transient_local(); diff --git a/map/map_tf_generator/nodes/map_tf_generator.cpp b/map/map_tf_generator/nodes/map_tf_generator.cpp index 2cd2d7c9a39b5..53bc5075ec969 100644 --- a/map/map_tf_generator/nodes/map_tf_generator.cpp +++ b/map/map_tf_generator/nodes/map_tf_generator.cpp @@ -32,7 +32,7 @@ class MapTFGenerator : public rclcpp::Node viewer_frame_ = declare_parameter("viewer_frame", "viewer"); sub_ = create_subscription( - "pointcloud_map", rclcpp::QoS{1}, + "pointcloud_map", rclcpp::QoS{1}.transient_local(), std::bind(&MapTFGenerator::Callback, this, std::placeholders::_1)); static_broadcaster_ = std::make_shared(this); diff --git a/perception/object_recognition/prediction/map_based_prediction/src/map_based_prediction_ros.cpp b/perception/object_recognition/prediction/map_based_prediction/src/map_based_prediction_ros.cpp index 8bb88c820d99d..b7cdf8f13f09d 100644 --- a/perception/object_recognition/prediction/map_based_prediction/src/map_based_prediction_ros.cpp +++ b/perception/object_recognition/prediction/map_based_prediction/src/map_based_prediction_ros.cpp @@ -196,7 +196,7 @@ MapBasedPredictionROS::MapBasedPredictionROS() "/perception/object_recognition/tracking/objects", 1, std::bind(&MapBasedPredictionROS::objectsCallback, this, std::placeholders::_1)); sub_map_ = this->create_subscription( - "/vector_map", 10, + "/vector_map", rclcpp::QoS{10}.transient_local(), std::bind(&MapBasedPredictionROS::mapCallback, this, std::placeholders::_1)); pub_objects_ = this->create_publisher( diff --git a/perception/traffic_light_recognition/traffic_light_map_based_detector/src/node.cpp b/perception/traffic_light_recognition/traffic_light_map_based_detector/src/node.cpp index 7ce66b3937fe6..548a1cde07020 100644 --- a/perception/traffic_light_recognition/traffic_light_map_based_detector/src/node.cpp +++ b/perception/traffic_light_recognition/traffic_light_map_based_detector/src/node.cpp @@ -47,7 +47,7 @@ namespace traffic_light // subscribers map_sub_ = create_subscription( - "input/vector_map", 1, std::bind(&MapBasedDetector::mapCallback, this, _1)); + "input/vector_map", rclcpp::QoS{1}.transient_local(), std::bind(&MapBasedDetector::mapCallback, this, _1)); camera_info_sub_ = create_subscription( "input/camera_info", 1, std::bind(&MapBasedDetector::cameraInfoCallback, this, _1)); route_sub_ = create_subscription( diff --git a/planning/mission_planning/mission_planner/src/mission_planner_lanelet2/mission_planner_lanelet2.cpp b/planning/mission_planning/mission_planner/src/mission_planner_lanelet2/mission_planner_lanelet2.cpp index c30891cc1cf08..9b1dd21ee2796 100644 --- a/planning/mission_planning/mission_planner/src/mission_planner_lanelet2/mission_planner_lanelet2.cpp +++ b/planning/mission_planning/mission_planner/src/mission_planner_lanelet2/mission_planner_lanelet2.cpp @@ -126,7 +126,7 @@ MissionPlannerLanelet2::MissionPlannerLanelet2() { using std::placeholders::_1; map_subscriber_ = create_subscription( - "input/vector_map", 10, std::bind( + "input/vector_map", rclcpp::QoS{10}.transient_local(), std::bind( &MissionPlannerLanelet2::mapCallback, this, _1)); } diff --git a/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/src/node.cpp b/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/src/node.cpp index 7687444b0b551..547ce59c0676b 100644 --- a/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/src/node.cpp +++ b/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/src/node.cpp @@ -84,7 +84,7 @@ BehaviorVelocityPlannerNode::BehaviorVelocityPlannerNode() "input/vehicle_velocity", 1, std::bind(&BehaviorVelocityPlannerNode::onVehicleVelocity, this, _1)); sub_lanelet_map_ = this->create_subscription( - "input/vector_map", 10, std::bind(&BehaviorVelocityPlannerNode::onLaneletMap, this, _1)); + "input/vector_map", rclcpp::QoS(10).transient_local(), std::bind(&BehaviorVelocityPlannerNode::onLaneletMap, this, _1)); sub_traffic_light_states_ = this->create_subscription( "input/traffic_light_states", 10, diff --git a/planning/scenario_planning/lane_driving/behavior_planning/lane_change_planner/src/lane_changer.cpp b/planning/scenario_planning/lane_driving/behavior_planning/lane_change_planner/src/lane_changer.cpp index 2331384583438..64cb0817cdf25 100644 --- a/planning/scenario_planning/lane_driving/behavior_planning/lane_change_planner/src/lane_changer.cpp +++ b/planning/scenario_planning/lane_driving/behavior_planning/lane_change_planner/src/lane_changer.cpp @@ -110,7 +110,7 @@ void LaneChanger::init() // route_handler vector_map_subscriber_ = create_subscription( - "input/vector_map", rclcpp::QoS{1}, std::bind( + "input/vector_map", rclcpp::QoS{1}.transient_local(), std::bind( &RouteHandler::mapCallback, &(*route_handler_ptr_), std::placeholders::_1)); route_subscriber_ = diff --git a/planning/scenario_planning/lane_driving/behavior_planning/turn_signal_decider/src/turn_signal_decider_core.cpp b/planning/scenario_planning/lane_driving/behavior_planning/turn_signal_decider/src/turn_signal_decider_core.cpp index ec29555fbc4ec..846a743b35216 100644 --- a/planning/scenario_planning/lane_driving/behavior_planning/turn_signal_decider/src/turn_signal_decider_core.cpp +++ b/planning/scenario_planning/lane_driving/behavior_planning/turn_signal_decider/src/turn_signal_decider_core.cpp @@ -49,7 +49,7 @@ TurnSignalDecider::TurnSignalDecider( "input/path_with_lane_id", rclcpp::QoS{1}, std::bind(&DataManager::onPathWithLaneId, &data_, _1)); map_subscription_ = this->create_subscription( - "input/vector_map", rclcpp::QoS{1}, std::bind(&DataManager::onLaneletMap, &data_, _1)); + "input/vector_map", rclcpp::QoS{1}.transient_local(), std::bind(&DataManager::onLaneletMap, &data_, _1)); // get ROS parameters parameters_.lane_change_search_distance = this->declare_parameter( diff --git a/planning/scenario_planning/parking/costmap_generator/nodes/costmap_generator/costmap_generator_node.cpp b/planning/scenario_planning/parking/costmap_generator/nodes/costmap_generator/costmap_generator_node.cpp index e8f2ffa39ca5f..c286f32c9497f 100644 --- a/planning/scenario_planning/parking/costmap_generator/nodes/costmap_generator/costmap_generator_node.cpp +++ b/planning/scenario_planning/parking/costmap_generator/nodes/costmap_generator/costmap_generator_node.cpp @@ -120,7 +120,7 @@ CostmapGenerator::CostmapGenerator() sub_points_ = this->create_subscription( "input/points_no_ground", 1, std::bind(&CostmapGenerator::onPoints, this, _1)); sub_lanelet_bin_map_ = this->create_subscription( - "input/vector_map", 1, std::bind(&CostmapGenerator::onLaneletMapBin, this, _1)); + "input/vector_map", rclcpp::QoS(1).transient_local(), std::bind(&CostmapGenerator::onLaneletMapBin, this, _1)); sub_scenario_ = this->create_subscription( "input/scenario", 1, std::bind(&CostmapGenerator::onScenario, this, _1)); diff --git a/planning/scenario_planning/scenario_selector/src/scenario_selector_node/scenario_selector_node.cpp b/planning/scenario_planning/scenario_selector/src/scenario_selector_node/scenario_selector_node.cpp index 45b07e5463322..71982d795d05e 100644 --- a/planning/scenario_planning/scenario_selector/src/scenario_selector_node/scenario_selector_node.cpp +++ b/planning/scenario_planning/scenario_selector/src/scenario_selector_node/scenario_selector_node.cpp @@ -318,7 +318,7 @@ ScenarioSelectorNode::ScenarioSelectorNode() "input/parking/trajectory", rclcpp::QoS{1}, createCallback(&input_parking_.buf_trajectory)); sub_lanelet_map_ = this->create_subscription( - "input/lanelet_map", rclcpp::QoS{1}, + "input/lanelet_map", rclcpp::QoS{1}.transient_local(), std::bind(&ScenarioSelectorNode::onMap, this, std::placeholders::_1)); sub_route_ = this->create_subscription( "input/route", rclcpp::QoS{1},