Skip to content

Commit 8793e98

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

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
@@ -82,14 +82,14 @@ BehaviorVelocityPlannerNode::BehaviorVelocityPlannerNode(const rclcpp::NodeOptio
8282
// Trigger Subscriber
8383
trigger_sub_path_with_lane_id_ =
8484
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),
8686
createSubscriptionOptions(this));
8787

8888
// Subscribers
8989
sub_predicted_objects_ =
9090
this->create_subscription<autoware_auto_perception_msgs::msg::PredictedObjects>(
9191
"~/input/dynamic_objects", 1,
92-
std::bind(&BehaviorVelocityPlannerNode::onPredictedObjects, this, _1),
92+
std::bind(&BehaviorVelocityPlannerNode::on_predicted_objects, this, _1),
9393
createSubscriptionOptions(this));
9494
sub_no_ground_pointcloud_ = this->create_subscription<sensor_msgs::msg::PointCloud2>(
9595
"~/input/no_ground_pointcloud", rclcpp::SensorDataQoS(),
@@ -232,7 +232,7 @@ void BehaviorVelocityPlannerNode::onOccupancyGrid(
232232
planner_data_.occupancy_grid = msg;
233233
}
234234

235-
void BehaviorVelocityPlannerNode::onPredictedObjects(
235+
void BehaviorVelocityPlannerNode::on_predicted_objects(
236236
const autoware_auto_perception_msgs::msg::PredictedObjects::ConstSharedPtr msg)
237237
{
238238
std::lock_guard<std::mutex> lock(mutex_);
@@ -372,7 +372,7 @@ void BehaviorVelocityPlannerNode::onVirtualTrafficLightStates(
372372
planner_data_.virtual_traffic_light_states = msg;
373373
}
374374

375-
void BehaviorVelocityPlannerNode::onTrigger(
375+
void BehaviorVelocityPlannerNode::on_trigger(
376376
const autoware_auto_planning_msgs::msg::PathWithLaneId::ConstSharedPtr input_path_msg)
377377
{
378378
std::unique_lock<std::mutex> lk(mutex_);

planning/behavior_velocity_planner/src/node.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -78,9 +78,9 @@ class BehaviorVelocityPlannerNode : public rclcpp::Node
7878
rclcpp::Subscription<nav_msgs::msg::OccupancyGrid>::SharedPtr sub_occupancy_grid_;
7979
rclcpp::Subscription<VelocityLimit>::SharedPtr sub_external_velocity_limit_;
8080

81-
void onTrigger(
81+
void on_trigger(
8282
const autoware_auto_planning_msgs::msg::PathWithLaneId::ConstSharedPtr input_path_msg);
83-
void onPredictedObjects(
83+
void on_predicted_objects(
8484
const autoware_auto_perception_msgs::msg::PredictedObjects::ConstSharedPtr msg);
8585
void onNoGroundPointCloud(const sensor_msgs::msg::PointCloud2::ConstSharedPtr msg);
8686
void onOdometry(const nav_msgs::msg::Odometry::ConstSharedPtr msg);

0 commit comments

Comments
 (0)