Skip to content

Commit

Permalink
fix(autoware_behavior_velocity_planner): fix naming issues
Browse files Browse the repository at this point in the history
Signed-off-by: Esteve Fernandez <[email protected]>
  • Loading branch information
esteve committed Apr 12, 2024
1 parent 0e7be0c commit 44bd1bd
Show file tree
Hide file tree
Showing 2 changed files with 12 additions and 12 deletions.
16 changes: 8 additions & 8 deletions planning/behavior_velocity_planner/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -108,11 +108,11 @@ BehaviorVelocityPlannerNode::BehaviorVelocityPlannerNode(const rclcpp::NodeOptio
sub_traffic_signals_ =
this->create_subscription<autoware_perception_msgs::msg::TrafficSignalArray>(
"~/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<VelocityLimit>(
"~/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<tier4_v2x_msgs::msg::VirtualTrafficLightStateArray>(
"~/input/virtual_traffic_light_states", 1,
Expand All @@ -126,7 +126,7 @@ BehaviorVelocityPlannerNode::BehaviorVelocityPlannerNode(const rclcpp::NodeOptio
"~/service/load_plugin", std::bind(&BehaviorVelocityPlannerNode::onLoadPlugin, this, _1, _2));
srv_unload_plugin_ = create_service<UnloadPlugin>(
"~/service/unload_plugin",
std::bind(&BehaviorVelocityPlannerNode::onUnloadPlugin, this, _1, _2));
std::bind(&BehaviorVelocityPlannerNode::on_unload_plugin, this, _1, _2));

// set velocity smoother param
onParam();
Expand Down Expand Up @@ -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)
{
Expand Down Expand Up @@ -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<std::mutex> lock(mutex_);
Expand Down Expand Up @@ -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<std::mutex> lock(mutex_);
planner_data_.external_velocity_limit = *msg;
Expand Down Expand Up @@ -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);
}
}

Expand Down Expand Up @@ -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;
Expand Down
8 changes: 4 additions & 4 deletions planning/behavior_velocity_planner/src/node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -86,20 +86,20 @@ 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
rclcpp::Publisher<autoware_auto_planning_msgs::msg::Path>::SharedPtr path_pub_;
rclcpp::Publisher<diagnostic_msgs::msg::DiagnosticStatus>::SharedPtr stop_reason_diag_pub_;
rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::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_;
Expand All @@ -115,7 +115,7 @@ class BehaviorVelocityPlannerNode : public rclcpp::Node

rclcpp::Service<LoadPlugin>::SharedPtr srv_load_plugin_;
rclcpp::Service<UnloadPlugin>::SharedPtr srv_unload_plugin_;
void onUnloadPlugin(
void on_unload_plugin(
const UnloadPlugin::Request::SharedPtr request,
const UnloadPlugin::Response::SharedPtr response);
void onLoadPlugin(
Expand Down

0 comments on commit 44bd1bd

Please sign in to comment.