@@ -82,14 +82,14 @@ BehaviorVelocityPlannerNode::BehaviorVelocityPlannerNode(const rclcpp::NodeOptio
82
82
// Trigger Subscriber
83
83
trigger_sub_path_with_lane_id_ =
84
84
this ->create_subscription <autoware_auto_planning_msgs::msg::PathWithLaneId>(
85
- " ~/input/path_with_lane_id" , 1 , std::bind (&BehaviorVelocityPlannerNode::onTrigger , this , _1),
85
+ " ~/input/path_with_lane_id" , 1 , std::bind (&BehaviorVelocityPlannerNode::on_trigger , this , _1),
86
86
createSubscriptionOptions (this ));
87
87
88
88
// Subscribers
89
89
sub_predicted_objects_ =
90
90
this ->create_subscription <autoware_auto_perception_msgs::msg::PredictedObjects>(
91
91
" ~/input/dynamic_objects" , 1 ,
92
- std::bind (&BehaviorVelocityPlannerNode::onPredictedObjects , this , _1),
92
+ std::bind (&BehaviorVelocityPlannerNode::on_predicted_objects , this , _1),
93
93
createSubscriptionOptions (this ));
94
94
sub_no_ground_pointcloud_ = this ->create_subscription <sensor_msgs::msg::PointCloud2>(
95
95
" ~/input/no_ground_pointcloud" , rclcpp::SensorDataQoS (),
@@ -232,7 +232,7 @@ void BehaviorVelocityPlannerNode::onOccupancyGrid(
232
232
planner_data_.occupancy_grid = msg;
233
233
}
234
234
235
- void BehaviorVelocityPlannerNode::onPredictedObjects (
235
+ void BehaviorVelocityPlannerNode::on_predicted_objects (
236
236
const autoware_auto_perception_msgs::msg::PredictedObjects::ConstSharedPtr msg)
237
237
{
238
238
std::lock_guard<std::mutex> lock (mutex_);
@@ -372,7 +372,7 @@ void BehaviorVelocityPlannerNode::onVirtualTrafficLightStates(
372
372
planner_data_.virtual_traffic_light_states = msg;
373
373
}
374
374
375
- void BehaviorVelocityPlannerNode::onTrigger (
375
+ void BehaviorVelocityPlannerNode::on_trigger (
376
376
const autoware_auto_planning_msgs::msg::PathWithLaneId::ConstSharedPtr input_path_msg)
377
377
{
378
378
std::unique_lock<std::mutex> lk (mutex_);
0 commit comments