From db1803bfd83faa2e4373a6aa1406e5aa7fe12349 Mon Sep 17 00:00:00 2001 From: Esteve Fernandez Date: Fri, 12 Apr 2024 17:14:20 +0200 Subject: [PATCH] fix(autoware_behavior_velocity_planner): fix naming issues Signed-off-by: Esteve Fernandez --- planning/behavior_velocity_planner/src/node.cpp | 8 ++++---- planning/behavior_velocity_planner/src/node.hpp | 4 ++-- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/planning/behavior_velocity_planner/src/node.cpp b/planning/behavior_velocity_planner/src/node.cpp index 72d69add0d163..249d9312b2fc9 100644 --- a/planning/behavior_velocity_planner/src/node.cpp +++ b/planning/behavior_velocity_planner/src/node.cpp @@ -93,7 +93,7 @@ BehaviorVelocityPlannerNode::BehaviorVelocityPlannerNode(const rclcpp::NodeOptio createSubscriptionOptions(this)); sub_no_ground_pointcloud_ = this->create_subscription( "~/input/no_ground_pointcloud", rclcpp::SensorDataQoS(), - std::bind(&BehaviorVelocityPlannerNode::onNoGroundPointCloud, this, _1), + std::bind(&BehaviorVelocityPlannerNode::on_no_ground_point_cloud, this, _1), createSubscriptionOptions(this)); sub_vehicle_odometry_ = this->create_subscription( "~/input/vehicle_odometry", 1, std::bind(&BehaviorVelocityPlannerNode::onOdometry, this, _1), @@ -116,7 +116,7 @@ BehaviorVelocityPlannerNode::BehaviorVelocityPlannerNode(const rclcpp::NodeOptio sub_virtual_traffic_light_states_ = this->create_subscription( "~/input/virtual_traffic_light_states", 1, - std::bind(&BehaviorVelocityPlannerNode::onVirtualTrafficLightStates, this, _1), + std::bind(&BehaviorVelocityPlannerNode::on_virtual_traffic_light_states, this, _1), createSubscriptionOptions(this)); sub_occupancy_grid_ = this->create_subscription( "~/input/occupancy_grid", 1, std::bind(&BehaviorVelocityPlannerNode::onOccupancyGrid, this, _1), @@ -239,7 +239,7 @@ void BehaviorVelocityPlannerNode::on_predicted_objects( planner_data_.predicted_objects = msg; } -void BehaviorVelocityPlannerNode::onNoGroundPointCloud( +void BehaviorVelocityPlannerNode::on_no_ground_point_cloud( const sensor_msgs::msg::PointCloud2::ConstSharedPtr msg) { geometry_msgs::msg::TransformStamped transform; @@ -365,7 +365,7 @@ void BehaviorVelocityPlannerNode::onExternalVelocityLimit(const VelocityLimit::C planner_data_.external_velocity_limit = *msg; } -void BehaviorVelocityPlannerNode::onVirtualTrafficLightStates( +void BehaviorVelocityPlannerNode::on_virtual_traffic_light_states( const tier4_v2x_msgs::msg::VirtualTrafficLightStateArray::ConstSharedPtr msg) { std::lock_guard lock(mutex_); diff --git a/planning/behavior_velocity_planner/src/node.hpp b/planning/behavior_velocity_planner/src/node.hpp index 1c3fe41544498..1cbec2191ced1 100644 --- a/planning/behavior_velocity_planner/src/node.hpp +++ b/planning/behavior_velocity_planner/src/node.hpp @@ -82,13 +82,13 @@ class BehaviorVelocityPlannerNode : public rclcpp::Node const autoware_auto_planning_msgs::msg::PathWithLaneId::ConstSharedPtr input_path_msg); void on_predicted_objects( const autoware_auto_perception_msgs::msg::PredictedObjects::ConstSharedPtr msg); - void onNoGroundPointCloud(const sensor_msgs::msg::PointCloud2::ConstSharedPtr msg); + void on_no_ground_point_cloud(const sensor_msgs::msg::PointCloud2::ConstSharedPtr msg); void onOdometry(const nav_msgs::msg::Odometry::ConstSharedPtr msg); void onAcceleration(const geometry_msgs::msg::AccelWithCovarianceStamped::ConstSharedPtr msg); void onLaneletMap(const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr msg); void onTrafficSignals( const autoware_perception_msgs::msg::TrafficSignalArray::ConstSharedPtr msg); - void onVirtualTrafficLightStates( + void on_virtual_traffic_light_states( const tier4_v2x_msgs::msg::VirtualTrafficLightStateArray::ConstSharedPtr msg); void onOccupancyGrid(const nav_msgs::msg::OccupancyGrid::ConstSharedPtr msg); void onExternalVelocityLimit(const VelocityLimit::ConstSharedPtr msg);