Skip to content

Commit 9dbeb9a

Browse files
committed
fix(autoware_behavior_velocity_planner): fix naming issues
Signed-off-by: Esteve Fernandez <esteve.fernandez@tier4.jp>
1 parent 112ccdf commit 9dbeb9a

File tree

4 files changed

+11
-11
lines changed

4 files changed

+11
-11
lines changed

planning/behavior_velocity_planner/src/node.cpp

+6-6
Original file line numberDiff line numberDiff line change
@@ -130,7 +130,7 @@ BehaviorVelocityPlannerNode::BehaviorVelocityPlannerNode(const rclcpp::NodeOptio
130130
std::bind(&BehaviorVelocityPlannerNode::on_unload_plugin, this, _1, _2));
131131

132132
// set velocity smoother param
133-
onParam();
133+
on_param();
134134

135135
// Publishers
136136
path_pub_ = this->create_publisher<autoware_auto_planning_msgs::msg::Path>("~/output/path", 1);
@@ -307,9 +307,9 @@ void BehaviorVelocityPlannerNode::on_acceleration(
307307
planner_data_.current_acceleration = msg;
308308
}
309309

310-
void BehaviorVelocityPlannerNode::onParam()
310+
void BehaviorVelocityPlannerNode::on_param()
311311
{
312-
// Note(VRichardJP): mutex lock is not necessary as onParam is only called once in the
312+
// Note(VRichardJP): mutex lock is not necessary as on_param is only called once in the
313313
// constructed. It would be required if it was a callback. std::lock_guard<std::mutex>
314314
// lock(mutex_);
315315
planner_data_.velocity_smoother_ =
@@ -398,20 +398,20 @@ void BehaviorVelocityPlannerNode::on_trigger(
398398
}
399399

400400
const autoware_auto_planning_msgs::msg::Path output_path_msg =
401-
generatePath(input_path_msg, planner_data_);
401+
generate_path(input_path_msg, planner_data_);
402402

403403
lk.unlock();
404404

405405
path_pub_->publish(output_path_msg);
406406
published_time_publisher_->publish_if_subscribed(path_pub_, output_path_msg.header.stamp);
407-
stop_reason_diag_pub_->publish(planner_manager_.getStopReasonDiag());
407+
stop_reason_diag_pub_->publish(planner_manager_.get_stop_reason_diag());
408408

409409
if (debug_viz_pub_->get_subscription_count() > 0) {
410410
publish_debug_marker(output_path_msg);
411411
}
412412
}
413413

414-
autoware_auto_planning_msgs::msg::Path BehaviorVelocityPlannerNode::generatePath(
414+
autoware_auto_planning_msgs::msg::Path BehaviorVelocityPlannerNode::generate_path(
415415
const autoware_auto_planning_msgs::msg::PathWithLaneId::ConstSharedPtr input_path_msg,
416416
const PlannerData & planner_data)
417417
{

planning/behavior_velocity_planner/src/node.hpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -92,7 +92,7 @@ class BehaviorVelocityPlannerNode : public rclcpp::Node
9292
const tier4_v2x_msgs::msg::VirtualTrafficLightStateArray::ConstSharedPtr msg);
9393
void on_occupancy_grid(const nav_msgs::msg::OccupancyGrid::ConstSharedPtr msg);
9494
void on_external_velocity_limit(const VelocityLimit::ConstSharedPtr msg);
95-
void onParam();
95+
void on_param();
9696

9797
// publisher
9898
rclcpp::Publisher<autoware_auto_planning_msgs::msg::Path>::SharedPtr path_pub_;
@@ -125,9 +125,9 @@ class BehaviorVelocityPlannerNode : public rclcpp::Node
125125
std::mutex mutex_;
126126

127127
// function
128-
geometry_msgs::msg::PoseStamped getCurrentPose();
128+
geometry_msgs::msg::PoseStamped get_current_pose();
129129
bool is_data_ready(const PlannerData & planner_data, rclcpp::Clock clock) const;
130-
autoware_auto_planning_msgs::msg::Path generatePath(
130+
autoware_auto_planning_msgs::msg::Path generate_path(
131131
const autoware_auto_planning_msgs::msg::PathWithLaneId::ConstSharedPtr input_path_msg,
132132
const PlannerData & planner_data);
133133

planning/behavior_velocity_planner/src/planner_manager.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -125,7 +125,7 @@ autoware_auto_planning_msgs::msg::PathWithLaneId BehaviorVelocityPlannerManager:
125125
return output_path_msg;
126126
}
127127

128-
diagnostic_msgs::msg::DiagnosticStatus BehaviorVelocityPlannerManager::getStopReasonDiag() const
128+
diagnostic_msgs::msg::DiagnosticStatus BehaviorVelocityPlannerManager::get_stop_reason_diag() const
129129
{
130130
return stop_reason_diag_;
131131
}

planning/behavior_velocity_planner/src/planner_manager.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -52,7 +52,7 @@ class BehaviorVelocityPlannerManager
5252
const std::shared_ptr<const PlannerData> & planner_data,
5353
const autoware_auto_planning_msgs::msg::PathWithLaneId & input_path_msg);
5454

55-
[[nodiscard]] diagnostic_msgs::msg::DiagnosticStatus getStopReasonDiag() const;
55+
[[nodiscard]] diagnostic_msgs::msg::DiagnosticStatus get_stop_reason_diag() const;
5656

5757
private:
5858
diagnostic_msgs::msg::DiagnosticStatus stop_reason_diag_;

0 commit comments

Comments
 (0)