|
40 | 40 |
|
41 | 41 | namespace
|
42 | 42 | {
|
43 |
| -rclcpp::SubscriptionOptions create_subscription_options(rclcpp::Node * node_ptr) |
| 43 | +rclcpp::SubscriptionOptions createSubscriptionOptions(rclcpp::Node * node_ptr) |
44 | 44 | {
|
45 | 45 | rclcpp::CallbackGroup::SharedPtr callback_group =
|
46 | 46 | node_ptr->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
|
@@ -81,44 +81,44 @@ BehaviorVelocityPlannerNode::BehaviorVelocityPlannerNode(const rclcpp::NodeOptio
|
81 | 81 | trigger_sub_path_with_lane_id_ =
|
82 | 82 | this->create_subscription<autoware_auto_planning_msgs::msg::PathWithLaneId>(
|
83 | 83 | "~/input/path_with_lane_id", 1, std::bind(&BehaviorVelocityPlannerNode::onTrigger, this, _1),
|
84 |
| - create_subscription_options(this)); |
| 84 | + createSubscriptionOptions(this)); |
85 | 85 |
|
86 | 86 | // Subscribers
|
87 | 87 | sub_predicted_objects_ =
|
88 | 88 | this->create_subscription<autoware_auto_perception_msgs::msg::PredictedObjects>(
|
89 | 89 | "~/input/dynamic_objects", 1,
|
90 | 90 | std::bind(&BehaviorVelocityPlannerNode::onPredictedObjects, this, _1),
|
91 |
| - create_subscription_options(this)); |
| 91 | + createSubscriptionOptions(this)); |
92 | 92 | sub_no_ground_pointcloud_ = this->create_subscription<sensor_msgs::msg::PointCloud2>(
|
93 | 93 | "~/input/no_ground_pointcloud", rclcpp::SensorDataQoS(),
|
94 | 94 | std::bind(&BehaviorVelocityPlannerNode::onNoGroundPointCloud, this, _1),
|
95 |
| - create_subscription_options(this)); |
| 95 | + createSubscriptionOptions(this)); |
96 | 96 | sub_vehicle_odometry_ = this->create_subscription<nav_msgs::msg::Odometry>(
|
97 | 97 | "~/input/vehicle_odometry", 1, std::bind(&BehaviorVelocityPlannerNode::onOdometry, this, _1),
|
98 |
| - create_subscription_options(this)); |
| 98 | + createSubscriptionOptions(this)); |
99 | 99 | sub_acceleration_ = this->create_subscription<geometry_msgs::msg::AccelWithCovarianceStamped>(
|
100 | 100 | "~/input/accel", 1, std::bind(&BehaviorVelocityPlannerNode::onAcceleration, this, _1),
|
101 |
| - create_subscription_options(this)); |
| 101 | + createSubscriptionOptions(this)); |
102 | 102 | sub_lanelet_map_ = this->create_subscription<autoware_auto_mapping_msgs::msg::HADMapBin>(
|
103 | 103 | "~/input/vector_map", rclcpp::QoS(10).transient_local(),
|
104 | 104 | std::bind(&BehaviorVelocityPlannerNode::onLaneletMap, this, _1),
|
105 |
| - create_subscription_options(this)); |
| 105 | + createSubscriptionOptions(this)); |
106 | 106 | sub_traffic_signals_ =
|
107 | 107 | this->create_subscription<autoware_perception_msgs::msg::TrafficSignalArray>(
|
108 | 108 | "~/input/traffic_signals", 1,
|
109 | 109 | std::bind(&BehaviorVelocityPlannerNode::onTrafficSignals, this, _1),
|
110 |
| - create_subscription_options(this)); |
| 110 | + createSubscriptionOptions(this)); |
111 | 111 | sub_external_velocity_limit_ = this->create_subscription<VelocityLimit>(
|
112 | 112 | "~/input/external_velocity_limit_mps", rclcpp::QoS{1}.transient_local(),
|
113 | 113 | std::bind(&BehaviorVelocityPlannerNode::onExternalVelocityLimit, this, _1));
|
114 | 114 | sub_virtual_traffic_light_states_ =
|
115 | 115 | this->create_subscription<tier4_v2x_msgs::msg::VirtualTrafficLightStateArray>(
|
116 | 116 | "~/input/virtual_traffic_light_states", 1,
|
117 | 117 | std::bind(&BehaviorVelocityPlannerNode::onVirtualTrafficLightStates, this, _1),
|
118 |
| - create_subscription_options(this)); |
| 118 | + createSubscriptionOptions(this)); |
119 | 119 | sub_occupancy_grid_ = this->create_subscription<nav_msgs::msg::OccupancyGrid>(
|
120 | 120 | "~/input/occupancy_grid", 1, std::bind(&BehaviorVelocityPlannerNode::onOccupancyGrid, this, _1),
|
121 |
| - create_subscription_options(this)); |
| 121 | + createSubscriptionOptions(this)); |
122 | 122 |
|
123 | 123 | srv_load_plugin_ = create_service<LoadPlugin>(
|
124 | 124 | "~/service/load_plugin", std::bind(&BehaviorVelocityPlannerNode::onLoadPlugin, this, _1, _2));
|
@@ -152,7 +152,7 @@ BehaviorVelocityPlannerNode::BehaviorVelocityPlannerNode(const rclcpp::NodeOptio
|
152 | 152 | // Initialize PlannerManager
|
153 | 153 | for (const auto & name : declare_parameter<std::vector<std::string>>("launch_modules")) {
|
154 | 154 | // workaround: Since ROS 2 can't get empty list, launcher set [''] on the parameter.
|
155 |
| - if (name.empty()) { |
| 155 | + if (name == "") { |
156 | 156 | break;
|
157 | 157 | }
|
158 | 158 | planner_manager_.launchScenePlugin(*this, name);
|
@@ -180,7 +180,7 @@ void BehaviorVelocityPlannerNode::onUnloadPlugin(
|
180 | 180 |
|
181 | 181 | // NOTE: argument planner_data must not be referenced for multithreading
|
182 | 182 | bool BehaviorVelocityPlannerNode::isDataReady(
|
183 |
| - const PlannerData & planner_data, rclcpp::Clock clock) const |
| 183 | + const PlannerData planner_data, rclcpp::Clock clock) const |
184 | 184 | {
|
185 | 185 | const auto & d = planner_data;
|
186 | 186 |
|
@@ -434,12 +434,11 @@ autoware_auto_planning_msgs::msg::Path BehaviorVelocityPlannerNode::generatePath
|
434 | 434 | std::make_shared<const PlannerData>(planner_data), *input_path_msg);
|
435 | 435 |
|
436 | 436 | // screening
|
437 |
| - const auto filtered_path = |
438 |
| - ::behavior_velocity_planner::filterLitterPathPoint(to_path(velocity_planned_path)); |
| 437 | + const auto filtered_path = ::behavior_velocity_planner::filterLitterPathPoint(to_path(velocity_planned_path)); |
439 | 438 |
|
440 | 439 | // interpolation
|
441 |
| - const auto interpolated_path_msg = ::behavior_velocity_planner::interpolatePath( |
442 |
| - filtered_path, forward_path_length_, behavior_output_path_interval_); |
| 440 | + const auto interpolated_path_msg = |
| 441 | + ::behavior_velocity_planner::interpolatePath(filtered_path, forward_path_length_, behavior_output_path_interval_); |
443 | 442 |
|
444 | 443 | // check stop point
|
445 | 444 | output_path_msg = ::behavior_velocity_planner::filterStopPathPoint(interpolated_path_msg);
|
|
0 commit comments