From 9dbeb9a20a52e505daf673d6cee884063a6e1ee6 Mon Sep 17 00:00:00 2001 From: Esteve Fernandez Date: Fri, 12 Apr 2024 17:35:54 +0200 Subject: [PATCH] fix(autoware_behavior_velocity_planner): fix naming issues Signed-off-by: Esteve Fernandez --- planning/behavior_velocity_planner/src/node.cpp | 12 ++++++------ planning/behavior_velocity_planner/src/node.hpp | 6 +++--- .../src/planner_manager.cpp | 2 +- .../src/planner_manager.hpp | 2 +- 4 files changed, 11 insertions(+), 11 deletions(-) diff --git a/planning/behavior_velocity_planner/src/node.cpp b/planning/behavior_velocity_planner/src/node.cpp index f0c6cce37b060..fbd36e2f2d30a 100644 --- a/planning/behavior_velocity_planner/src/node.cpp +++ b/planning/behavior_velocity_planner/src/node.cpp @@ -130,7 +130,7 @@ BehaviorVelocityPlannerNode::BehaviorVelocityPlannerNode(const rclcpp::NodeOptio std::bind(&BehaviorVelocityPlannerNode::on_unload_plugin, this, _1, _2)); // set velocity smoother param - onParam(); + on_param(); // Publishers path_pub_ = this->create_publisher("~/output/path", 1); @@ -307,9 +307,9 @@ void BehaviorVelocityPlannerNode::on_acceleration( planner_data_.current_acceleration = msg; } -void BehaviorVelocityPlannerNode::onParam() +void BehaviorVelocityPlannerNode::on_param() { - // Note(VRichardJP): mutex lock is not necessary as onParam is only called once in the + // Note(VRichardJP): mutex lock is not necessary as on_param is only called once in the // constructed. It would be required if it was a callback. std::lock_guard // lock(mutex_); planner_data_.velocity_smoother_ = @@ -398,20 +398,20 @@ void BehaviorVelocityPlannerNode::on_trigger( } const autoware_auto_planning_msgs::msg::Path output_path_msg = - generatePath(input_path_msg, planner_data_); + generate_path(input_path_msg, planner_data_); lk.unlock(); path_pub_->publish(output_path_msg); published_time_publisher_->publish_if_subscribed(path_pub_, output_path_msg.header.stamp); - stop_reason_diag_pub_->publish(planner_manager_.getStopReasonDiag()); + stop_reason_diag_pub_->publish(planner_manager_.get_stop_reason_diag()); if (debug_viz_pub_->get_subscription_count() > 0) { publish_debug_marker(output_path_msg); } } -autoware_auto_planning_msgs::msg::Path BehaviorVelocityPlannerNode::generatePath( +autoware_auto_planning_msgs::msg::Path BehaviorVelocityPlannerNode::generate_path( const autoware_auto_planning_msgs::msg::PathWithLaneId::ConstSharedPtr input_path_msg, const PlannerData & planner_data) { diff --git a/planning/behavior_velocity_planner/src/node.hpp b/planning/behavior_velocity_planner/src/node.hpp index a0c85e9ca93b1..3b5a264c1d792 100644 --- a/planning/behavior_velocity_planner/src/node.hpp +++ b/planning/behavior_velocity_planner/src/node.hpp @@ -92,7 +92,7 @@ class BehaviorVelocityPlannerNode : public rclcpp::Node const tier4_v2x_msgs::msg::VirtualTrafficLightStateArray::ConstSharedPtr msg); void on_occupancy_grid(const nav_msgs::msg::OccupancyGrid::ConstSharedPtr msg); void on_external_velocity_limit(const VelocityLimit::ConstSharedPtr msg); - void onParam(); + void on_param(); // publisher rclcpp::Publisher::SharedPtr path_pub_; @@ -125,9 +125,9 @@ class BehaviorVelocityPlannerNode : public rclcpp::Node std::mutex mutex_; // function - geometry_msgs::msg::PoseStamped getCurrentPose(); + geometry_msgs::msg::PoseStamped get_current_pose(); bool is_data_ready(const PlannerData & planner_data, rclcpp::Clock clock) const; - autoware_auto_planning_msgs::msg::Path generatePath( + autoware_auto_planning_msgs::msg::Path generate_path( const autoware_auto_planning_msgs::msg::PathWithLaneId::ConstSharedPtr input_path_msg, const PlannerData & planner_data); diff --git a/planning/behavior_velocity_planner/src/planner_manager.cpp b/planning/behavior_velocity_planner/src/planner_manager.cpp index fc8dd672ab13d..72393e3e7a3ac 100644 --- a/planning/behavior_velocity_planner/src/planner_manager.cpp +++ b/planning/behavior_velocity_planner/src/planner_manager.cpp @@ -125,7 +125,7 @@ autoware_auto_planning_msgs::msg::PathWithLaneId BehaviorVelocityPlannerManager: return output_path_msg; } -diagnostic_msgs::msg::DiagnosticStatus BehaviorVelocityPlannerManager::getStopReasonDiag() const +diagnostic_msgs::msg::DiagnosticStatus BehaviorVelocityPlannerManager::get_stop_reason_diag() const { return stop_reason_diag_; } diff --git a/planning/behavior_velocity_planner/src/planner_manager.hpp b/planning/behavior_velocity_planner/src/planner_manager.hpp index 59773eeb937d0..8c3caa8e88d60 100644 --- a/planning/behavior_velocity_planner/src/planner_manager.hpp +++ b/planning/behavior_velocity_planner/src/planner_manager.hpp @@ -52,7 +52,7 @@ class BehaviorVelocityPlannerManager const std::shared_ptr & planner_data, const autoware_auto_planning_msgs::msg::PathWithLaneId & input_path_msg); - [[nodiscard]] diagnostic_msgs::msg::DiagnosticStatus getStopReasonDiag() const; + [[nodiscard]] diagnostic_msgs::msg::DiagnosticStatus get_stop_reason_diag() const; private: diagnostic_msgs::msg::DiagnosticStatus stop_reason_diag_;