diff --git a/planning/behavior_velocity_planner/src/node.cpp b/planning/behavior_velocity_planner/src/node.cpp index cf218efee4330..bdca748850642 100644 --- a/planning/behavior_velocity_planner/src/node.cpp +++ b/planning/behavior_velocity_planner/src/node.cpp @@ -108,11 +108,11 @@ BehaviorVelocityPlannerNode::BehaviorVelocityPlannerNode(const rclcpp::NodeOptio sub_traffic_signals_ = this->create_subscription( "~/input/traffic_signals", 1, - std::bind(&BehaviorVelocityPlannerNode::onTrafficSignals, this, _1), + std::bind(&BehaviorVelocityPlannerNode::on_traffic_signals, this, _1), create_subscription_options(this)); sub_external_velocity_limit_ = this->create_subscription( "~/input/external_velocity_limit_mps", rclcpp::QoS{1}.transient_local(), - std::bind(&BehaviorVelocityPlannerNode::onExternalVelocityLimit, this, _1)); + std::bind(&BehaviorVelocityPlannerNode::on_external_velocity_limit, this, _1)); sub_virtual_traffic_light_states_ = this->create_subscription( "~/input/virtual_traffic_light_states", 1, @@ -126,7 +126,7 @@ BehaviorVelocityPlannerNode::BehaviorVelocityPlannerNode(const rclcpp::NodeOptio "~/service/load_plugin", std::bind(&BehaviorVelocityPlannerNode::onLoadPlugin, this, _1, _2)); srv_unload_plugin_ = create_service( "~/service/unload_plugin", - std::bind(&BehaviorVelocityPlannerNode::onUnloadPlugin, this, _1, _2)); + std::bind(&BehaviorVelocityPlannerNode::on_unload_plugin, this, _1, _2)); // set velocity smoother param onParam(); @@ -172,7 +172,7 @@ void BehaviorVelocityPlannerNode::onLoadPlugin( planner_manager_.launchScenePlugin(*this, request->plugin_name); } -void BehaviorVelocityPlannerNode::onUnloadPlugin( +void BehaviorVelocityPlannerNode::on_unload_plugin( const UnloadPlugin::Request::SharedPtr request, [[maybe_unused]] const UnloadPlugin::Response::SharedPtr response) { @@ -324,7 +324,7 @@ void BehaviorVelocityPlannerNode::on_lanelet_map( has_received_map_ = true; } -void BehaviorVelocityPlannerNode::onTrafficSignals( +void BehaviorVelocityPlannerNode::on_traffic_signals( const autoware_perception_msgs::msg::TrafficSignalArray::ConstSharedPtr msg) { std::lock_guard lock(mutex_); @@ -359,7 +359,7 @@ void BehaviorVelocityPlannerNode::onTrafficSignals( } } -void BehaviorVelocityPlannerNode::onExternalVelocityLimit(const VelocityLimit::ConstSharedPtr msg) +void BehaviorVelocityPlannerNode::on_external_velocity_limit(const VelocityLimit::ConstSharedPtr msg) { std::lock_guard lock(mutex_); planner_data_.external_velocity_limit = *msg; @@ -406,7 +406,7 @@ void BehaviorVelocityPlannerNode::on_trigger( stop_reason_diag_pub_->publish(planner_manager_.getStopReasonDiag()); if (debug_viz_pub_->get_subscription_count() > 0) { - publishDebugMarker(output_path_msg); + publish_debug_marker(output_path_msg); } } @@ -456,7 +456,7 @@ autoware_auto_planning_msgs::msg::Path BehaviorVelocityPlannerNode::generatePath return output_path_msg; } -void BehaviorVelocityPlannerNode::publishDebugMarker( +void BehaviorVelocityPlannerNode::publish_debug_marker( const autoware_auto_planning_msgs::msg::Path & path) { visualization_msgs::msg::MarkerArray output_msg; diff --git a/planning/behavior_velocity_planner/src/node.hpp b/planning/behavior_velocity_planner/src/node.hpp index fc75ad59f550e..039bfbefd8254 100644 --- a/planning/behavior_velocity_planner/src/node.hpp +++ b/planning/behavior_velocity_planner/src/node.hpp @@ -86,12 +86,12 @@ class BehaviorVelocityPlannerNode : public rclcpp::Node void on_odometry(const nav_msgs::msg::Odometry::ConstSharedPtr msg); void on_acceleration(const geometry_msgs::msg::AccelWithCovarianceStamped::ConstSharedPtr msg); void on_lanelet_map(const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr msg); - void onTrafficSignals( + void on_traffic_signals( const autoware_perception_msgs::msg::TrafficSignalArray::ConstSharedPtr msg); void on_virtual_traffic_light_states( const tier4_v2x_msgs::msg::VirtualTrafficLightStateArray::ConstSharedPtr msg); void on_occupancy_grid(const nav_msgs::msg::OccupancyGrid::ConstSharedPtr msg); - void onExternalVelocityLimit(const VelocityLimit::ConstSharedPtr msg); + void on_external_velocity_limit(const VelocityLimit::ConstSharedPtr msg); void onParam(); // publisher @@ -99,7 +99,7 @@ class BehaviorVelocityPlannerNode : public rclcpp::Node rclcpp::Publisher::SharedPtr stop_reason_diag_pub_; rclcpp::Publisher::SharedPtr debug_viz_pub_; - void publishDebugMarker(const autoware_auto_planning_msgs::msg::Path & path); + void publish_debug_marker(const autoware_auto_planning_msgs::msg::Path & path); // parameter double forward_path_length_; @@ -115,7 +115,7 @@ class BehaviorVelocityPlannerNode : public rclcpp::Node rclcpp::Service::SharedPtr srv_load_plugin_; rclcpp::Service::SharedPtr srv_unload_plugin_; - void onUnloadPlugin( + void on_unload_plugin( const UnloadPlugin::Request::SharedPtr request, const UnloadPlugin::Response::SharedPtr response); void onLoadPlugin(