@@ -93,7 +93,7 @@ BehaviorVelocityPlannerNode::BehaviorVelocityPlannerNode(const rclcpp::NodeOptio
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 (),
96
- std::bind (&BehaviorVelocityPlannerNode::onNoGroundPointCloud , this , _1),
96
+ std::bind (&BehaviorVelocityPlannerNode::on_no_ground_point_cloud , this , _1),
97
97
createSubscriptionOptions (this ));
98
98
sub_vehicle_odometry_ = this ->create_subscription <nav_msgs::msg::Odometry>(
99
99
" ~/input/vehicle_odometry" , 1 , std::bind (&BehaviorVelocityPlannerNode::onOdometry, this , _1),
@@ -116,7 +116,7 @@ BehaviorVelocityPlannerNode::BehaviorVelocityPlannerNode(const rclcpp::NodeOptio
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 ,
119
- std::bind (&BehaviorVelocityPlannerNode::onVirtualTrafficLightStates , this , _1),
119
+ std::bind (&BehaviorVelocityPlannerNode::on_virtual_traffic_light_states , this , _1),
120
120
createSubscriptionOptions (this ));
121
121
sub_occupancy_grid_ = this ->create_subscription <nav_msgs::msg::OccupancyGrid>(
122
122
" ~/input/occupancy_grid" , 1 , std::bind (&BehaviorVelocityPlannerNode::onOccupancyGrid, this , _1),
@@ -239,7 +239,7 @@ void BehaviorVelocityPlannerNode::on_predicted_objects(
239
239
planner_data_.predicted_objects = msg;
240
240
}
241
241
242
- void BehaviorVelocityPlannerNode::onNoGroundPointCloud (
242
+ void BehaviorVelocityPlannerNode::on_no_ground_point_cloud (
243
243
const sensor_msgs::msg::PointCloud2::ConstSharedPtr msg)
244
244
{
245
245
geometry_msgs::msg::TransformStamped transform;
@@ -365,7 +365,7 @@ void BehaviorVelocityPlannerNode::onExternalVelocityLimit(const VelocityLimit::C
365
365
planner_data_.external_velocity_limit = *msg;
366
366
}
367
367
368
- void BehaviorVelocityPlannerNode::onVirtualTrafficLightStates (
368
+ void BehaviorVelocityPlannerNode::on_virtual_traffic_light_states (
369
369
const tier4_v2x_msgs::msg::VirtualTrafficLightStateArray::ConstSharedPtr msg)
370
370
{
371
371
std::lock_guard<std::mutex> lock (mutex_);
0 commit comments