Skip to content

Commit 44bd1bd

Browse files
committed
fix(autoware_behavior_velocity_planner): fix naming issues
Signed-off-by: Esteve Fernandez <esteve.fernandez@tier4.jp>
1 parent 0e7be0c commit 44bd1bd

File tree

2 files changed

+12
-12
lines changed

2 files changed

+12
-12
lines changed

planning/behavior_velocity_planner/src/node.cpp

+8-8
Original file line numberDiff line numberDiff line change
@@ -108,11 +108,11 @@ BehaviorVelocityPlannerNode::BehaviorVelocityPlannerNode(const rclcpp::NodeOptio
108108
sub_traffic_signals_ =
109109
this->create_subscription<autoware_perception_msgs::msg::TrafficSignalArray>(
110110
"~/input/traffic_signals", 1,
111-
std::bind(&BehaviorVelocityPlannerNode::onTrafficSignals, this, _1),
111+
std::bind(&BehaviorVelocityPlannerNode::on_traffic_signals, this, _1),
112112
create_subscription_options(this));
113113
sub_external_velocity_limit_ = this->create_subscription<VelocityLimit>(
114114
"~/input/external_velocity_limit_mps", rclcpp::QoS{1}.transient_local(),
115-
std::bind(&BehaviorVelocityPlannerNode::onExternalVelocityLimit, this, _1));
115+
std::bind(&BehaviorVelocityPlannerNode::on_external_velocity_limit, this, _1));
116116
sub_virtual_traffic_light_states_ =
117117
this->create_subscription<tier4_v2x_msgs::msg::VirtualTrafficLightStateArray>(
118118
"~/input/virtual_traffic_light_states", 1,
@@ -126,7 +126,7 @@ BehaviorVelocityPlannerNode::BehaviorVelocityPlannerNode(const rclcpp::NodeOptio
126126
"~/service/load_plugin", std::bind(&BehaviorVelocityPlannerNode::onLoadPlugin, this, _1, _2));
127127
srv_unload_plugin_ = create_service<UnloadPlugin>(
128128
"~/service/unload_plugin",
129-
std::bind(&BehaviorVelocityPlannerNode::onUnloadPlugin, this, _1, _2));
129+
std::bind(&BehaviorVelocityPlannerNode::on_unload_plugin, this, _1, _2));
130130

131131
// set velocity smoother param
132132
onParam();
@@ -172,7 +172,7 @@ void BehaviorVelocityPlannerNode::onLoadPlugin(
172172
planner_manager_.launchScenePlugin(*this, request->plugin_name);
173173
}
174174

175-
void BehaviorVelocityPlannerNode::onUnloadPlugin(
175+
void BehaviorVelocityPlannerNode::on_unload_plugin(
176176
const UnloadPlugin::Request::SharedPtr request,
177177
[[maybe_unused]] const UnloadPlugin::Response::SharedPtr response)
178178
{
@@ -324,7 +324,7 @@ void BehaviorVelocityPlannerNode::on_lanelet_map(
324324
has_received_map_ = true;
325325
}
326326

327-
void BehaviorVelocityPlannerNode::onTrafficSignals(
327+
void BehaviorVelocityPlannerNode::on_traffic_signals(
328328
const autoware_perception_msgs::msg::TrafficSignalArray::ConstSharedPtr msg)
329329
{
330330
std::lock_guard<std::mutex> lock(mutex_);
@@ -359,7 +359,7 @@ void BehaviorVelocityPlannerNode::onTrafficSignals(
359359
}
360360
}
361361

362-
void BehaviorVelocityPlannerNode::onExternalVelocityLimit(const VelocityLimit::ConstSharedPtr msg)
362+
void BehaviorVelocityPlannerNode::on_external_velocity_limit(const VelocityLimit::ConstSharedPtr msg)
363363
{
364364
std::lock_guard<std::mutex> lock(mutex_);
365365
planner_data_.external_velocity_limit = *msg;
@@ -406,7 +406,7 @@ void BehaviorVelocityPlannerNode::on_trigger(
406406
stop_reason_diag_pub_->publish(planner_manager_.getStopReasonDiag());
407407

408408
if (debug_viz_pub_->get_subscription_count() > 0) {
409-
publishDebugMarker(output_path_msg);
409+
publish_debug_marker(output_path_msg);
410410
}
411411
}
412412

@@ -456,7 +456,7 @@ autoware_auto_planning_msgs::msg::Path BehaviorVelocityPlannerNode::generatePath
456456
return output_path_msg;
457457
}
458458

459-
void BehaviorVelocityPlannerNode::publishDebugMarker(
459+
void BehaviorVelocityPlannerNode::publish_debug_marker(
460460
const autoware_auto_planning_msgs::msg::Path & path)
461461
{
462462
visualization_msgs::msg::MarkerArray output_msg;

planning/behavior_velocity_planner/src/node.hpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -86,20 +86,20 @@ class BehaviorVelocityPlannerNode : public rclcpp::Node
8686
void on_odometry(const nav_msgs::msg::Odometry::ConstSharedPtr msg);
8787
void on_acceleration(const geometry_msgs::msg::AccelWithCovarianceStamped::ConstSharedPtr msg);
8888
void on_lanelet_map(const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr msg);
89-
void onTrafficSignals(
89+
void on_traffic_signals(
9090
const autoware_perception_msgs::msg::TrafficSignalArray::ConstSharedPtr msg);
9191
void on_virtual_traffic_light_states(
9292
const tier4_v2x_msgs::msg::VirtualTrafficLightStateArray::ConstSharedPtr msg);
9393
void on_occupancy_grid(const nav_msgs::msg::OccupancyGrid::ConstSharedPtr msg);
94-
void onExternalVelocityLimit(const VelocityLimit::ConstSharedPtr msg);
94+
void on_external_velocity_limit(const VelocityLimit::ConstSharedPtr msg);
9595
void onParam();
9696

9797
// publisher
9898
rclcpp::Publisher<autoware_auto_planning_msgs::msg::Path>::SharedPtr path_pub_;
9999
rclcpp::Publisher<diagnostic_msgs::msg::DiagnosticStatus>::SharedPtr stop_reason_diag_pub_;
100100
rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr debug_viz_pub_;
101101

102-
void publishDebugMarker(const autoware_auto_planning_msgs::msg::Path & path);
102+
void publish_debug_marker(const autoware_auto_planning_msgs::msg::Path & path);
103103

104104
// parameter
105105
double forward_path_length_;
@@ -115,7 +115,7 @@ class BehaviorVelocityPlannerNode : public rclcpp::Node
115115

116116
rclcpp::Service<LoadPlugin>::SharedPtr srv_load_plugin_;
117117
rclcpp::Service<UnloadPlugin>::SharedPtr srv_unload_plugin_;
118-
void onUnloadPlugin(
118+
void on_unload_plugin(
119119
const UnloadPlugin::Request::SharedPtr request,
120120
const UnloadPlugin::Response::SharedPtr response);
121121
void onLoadPlugin(

0 commit comments

Comments
 (0)