@@ -108,11 +108,11 @@ BehaviorVelocityPlannerNode::BehaviorVelocityPlannerNode(const rclcpp::NodeOptio
108
108
sub_traffic_signals_ =
109
109
this ->create_subscription <autoware_perception_msgs::msg::TrafficSignalArray>(
110
110
" ~/input/traffic_signals" , 1 ,
111
- std::bind (&BehaviorVelocityPlannerNode::onTrafficSignals , this , _1),
111
+ std::bind (&BehaviorVelocityPlannerNode::on_traffic_signals , this , _1),
112
112
create_subscription_options (this ));
113
113
sub_external_velocity_limit_ = this ->create_subscription <VelocityLimit>(
114
114
" ~/input/external_velocity_limit_mps" , rclcpp::QoS{1 }.transient_local (),
115
- std::bind (&BehaviorVelocityPlannerNode::onExternalVelocityLimit , this , _1));
115
+ std::bind (&BehaviorVelocityPlannerNode::on_external_velocity_limit , this , _1));
116
116
sub_virtual_traffic_light_states_ =
117
117
this ->create_subscription <tier4_v2x_msgs::msg::VirtualTrafficLightStateArray>(
118
118
" ~/input/virtual_traffic_light_states" , 1 ,
@@ -126,7 +126,7 @@ BehaviorVelocityPlannerNode::BehaviorVelocityPlannerNode(const rclcpp::NodeOptio
126
126
" ~/service/load_plugin" , std::bind (&BehaviorVelocityPlannerNode::onLoadPlugin, this , _1, _2));
127
127
srv_unload_plugin_ = create_service<UnloadPlugin>(
128
128
" ~/service/unload_plugin" ,
129
- std::bind (&BehaviorVelocityPlannerNode::onUnloadPlugin , this , _1, _2));
129
+ std::bind (&BehaviorVelocityPlannerNode::on_unload_plugin , this , _1, _2));
130
130
131
131
// set velocity smoother param
132
132
onParam ();
@@ -172,7 +172,7 @@ void BehaviorVelocityPlannerNode::onLoadPlugin(
172
172
planner_manager_.launchScenePlugin (*this , request->plugin_name );
173
173
}
174
174
175
- void BehaviorVelocityPlannerNode::onUnloadPlugin (
175
+ void BehaviorVelocityPlannerNode::on_unload_plugin (
176
176
const UnloadPlugin::Request::SharedPtr request,
177
177
[[maybe_unused]] const UnloadPlugin::Response::SharedPtr response)
178
178
{
@@ -324,7 +324,7 @@ void BehaviorVelocityPlannerNode::on_lanelet_map(
324
324
has_received_map_ = true ;
325
325
}
326
326
327
- void BehaviorVelocityPlannerNode::onTrafficSignals (
327
+ void BehaviorVelocityPlannerNode::on_traffic_signals (
328
328
const autoware_perception_msgs::msg::TrafficSignalArray::ConstSharedPtr msg)
329
329
{
330
330
std::lock_guard<std::mutex> lock (mutex_);
@@ -359,7 +359,7 @@ void BehaviorVelocityPlannerNode::onTrafficSignals(
359
359
}
360
360
}
361
361
362
- void BehaviorVelocityPlannerNode::onExternalVelocityLimit (const VelocityLimit::ConstSharedPtr msg)
362
+ void BehaviorVelocityPlannerNode::on_external_velocity_limit (const VelocityLimit::ConstSharedPtr msg)
363
363
{
364
364
std::lock_guard<std::mutex> lock (mutex_);
365
365
planner_data_.external_velocity_limit = *msg;
@@ -406,7 +406,7 @@ void BehaviorVelocityPlannerNode::on_trigger(
406
406
stop_reason_diag_pub_->publish (planner_manager_.getStopReasonDiag ());
407
407
408
408
if (debug_viz_pub_->get_subscription_count () > 0 ) {
409
- publishDebugMarker (output_path_msg);
409
+ publish_debug_marker (output_path_msg);
410
410
}
411
411
}
412
412
@@ -456,7 +456,7 @@ autoware_auto_planning_msgs::msg::Path BehaviorVelocityPlannerNode::generatePath
456
456
return output_path_msg;
457
457
}
458
458
459
- void BehaviorVelocityPlannerNode::publishDebugMarker (
459
+ void BehaviorVelocityPlannerNode::publish_debug_marker (
460
460
const autoware_auto_planning_msgs::msg::Path & path)
461
461
{
462
462
visualization_msgs::msg::MarkerArray output_msg;
0 commit comments