Skip to content

Commit db1803b

Browse files
committed
fix(autoware_behavior_velocity_planner): fix naming issues
Signed-off-by: Esteve Fernandez <esteve.fernandez@tier4.jp>
1 parent 8793e98 commit db1803b

File tree

2 files changed

+6
-6
lines changed

2 files changed

+6
-6
lines changed

planning/behavior_velocity_planner/src/node.cpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -93,7 +93,7 @@ BehaviorVelocityPlannerNode::BehaviorVelocityPlannerNode(const rclcpp::NodeOptio
9393
createSubscriptionOptions(this));
9494
sub_no_ground_pointcloud_ = this->create_subscription<sensor_msgs::msg::PointCloud2>(
9595
"~/input/no_ground_pointcloud", rclcpp::SensorDataQoS(),
96-
std::bind(&BehaviorVelocityPlannerNode::onNoGroundPointCloud, this, _1),
96+
std::bind(&BehaviorVelocityPlannerNode::on_no_ground_point_cloud, this, _1),
9797
createSubscriptionOptions(this));
9898
sub_vehicle_odometry_ = this->create_subscription<nav_msgs::msg::Odometry>(
9999
"~/input/vehicle_odometry", 1, std::bind(&BehaviorVelocityPlannerNode::onOdometry, this, _1),
@@ -116,7 +116,7 @@ BehaviorVelocityPlannerNode::BehaviorVelocityPlannerNode(const rclcpp::NodeOptio
116116
sub_virtual_traffic_light_states_ =
117117
this->create_subscription<tier4_v2x_msgs::msg::VirtualTrafficLightStateArray>(
118118
"~/input/virtual_traffic_light_states", 1,
119-
std::bind(&BehaviorVelocityPlannerNode::onVirtualTrafficLightStates, this, _1),
119+
std::bind(&BehaviorVelocityPlannerNode::on_virtual_traffic_light_states, this, _1),
120120
createSubscriptionOptions(this));
121121
sub_occupancy_grid_ = this->create_subscription<nav_msgs::msg::OccupancyGrid>(
122122
"~/input/occupancy_grid", 1, std::bind(&BehaviorVelocityPlannerNode::onOccupancyGrid, this, _1),
@@ -239,7 +239,7 @@ void BehaviorVelocityPlannerNode::on_predicted_objects(
239239
planner_data_.predicted_objects = msg;
240240
}
241241

242-
void BehaviorVelocityPlannerNode::onNoGroundPointCloud(
242+
void BehaviorVelocityPlannerNode::on_no_ground_point_cloud(
243243
const sensor_msgs::msg::PointCloud2::ConstSharedPtr msg)
244244
{
245245
geometry_msgs::msg::TransformStamped transform;
@@ -365,7 +365,7 @@ void BehaviorVelocityPlannerNode::onExternalVelocityLimit(const VelocityLimit::C
365365
planner_data_.external_velocity_limit = *msg;
366366
}
367367

368-
void BehaviorVelocityPlannerNode::onVirtualTrafficLightStates(
368+
void BehaviorVelocityPlannerNode::on_virtual_traffic_light_states(
369369
const tier4_v2x_msgs::msg::VirtualTrafficLightStateArray::ConstSharedPtr msg)
370370
{
371371
std::lock_guard<std::mutex> lock(mutex_);

planning/behavior_velocity_planner/src/node.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -82,13 +82,13 @@ class BehaviorVelocityPlannerNode : public rclcpp::Node
8282
const autoware_auto_planning_msgs::msg::PathWithLaneId::ConstSharedPtr input_path_msg);
8383
void on_predicted_objects(
8484
const autoware_auto_perception_msgs::msg::PredictedObjects::ConstSharedPtr msg);
85-
void onNoGroundPointCloud(const sensor_msgs::msg::PointCloud2::ConstSharedPtr msg);
85+
void on_no_ground_point_cloud(const sensor_msgs::msg::PointCloud2::ConstSharedPtr msg);
8686
void onOdometry(const nav_msgs::msg::Odometry::ConstSharedPtr msg);
8787
void onAcceleration(const geometry_msgs::msg::AccelWithCovarianceStamped::ConstSharedPtr msg);
8888
void onLaneletMap(const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr msg);
8989
void onTrafficSignals(
9090
const autoware_perception_msgs::msg::TrafficSignalArray::ConstSharedPtr msg);
91-
void onVirtualTrafficLightStates(
91+
void on_virtual_traffic_light_states(
9292
const tier4_v2x_msgs::msg::VirtualTrafficLightStateArray::ConstSharedPtr msg);
9393
void onOccupancyGrid(const nav_msgs::msg::OccupancyGrid::ConstSharedPtr msg);
9494
void onExternalVelocityLimit(const VelocityLimit::ConstSharedPtr msg);

0 commit comments

Comments
 (0)