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 8793e98 commit db1803b
Show file tree
Hide file tree
Showing 2 changed files with 6 additions and 6 deletions.
8 changes: 4 additions & 4 deletions planning/behavior_velocity_planner/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -93,7 +93,7 @@ BehaviorVelocityPlannerNode::BehaviorVelocityPlannerNode(const rclcpp::NodeOptio
createSubscriptionOptions(this));
sub_no_ground_pointcloud_ = this->create_subscription<sensor_msgs::msg::PointCloud2>(
"~/input/no_ground_pointcloud", rclcpp::SensorDataQoS(),
std::bind(&BehaviorVelocityPlannerNode::onNoGroundPointCloud, this, _1),
std::bind(&BehaviorVelocityPlannerNode::on_no_ground_point_cloud, this, _1),
createSubscriptionOptions(this));
sub_vehicle_odometry_ = this->create_subscription<nav_msgs::msg::Odometry>(
"~/input/vehicle_odometry", 1, std::bind(&BehaviorVelocityPlannerNode::onOdometry, this, _1),
Expand All @@ -116,7 +116,7 @@ BehaviorVelocityPlannerNode::BehaviorVelocityPlannerNode(const rclcpp::NodeOptio
sub_virtual_traffic_light_states_ =
this->create_subscription<tier4_v2x_msgs::msg::VirtualTrafficLightStateArray>(
"~/input/virtual_traffic_light_states", 1,
std::bind(&BehaviorVelocityPlannerNode::onVirtualTrafficLightStates, this, _1),
std::bind(&BehaviorVelocityPlannerNode::on_virtual_traffic_light_states, this, _1),
createSubscriptionOptions(this));
sub_occupancy_grid_ = this->create_subscription<nav_msgs::msg::OccupancyGrid>(
"~/input/occupancy_grid", 1, std::bind(&BehaviorVelocityPlannerNode::onOccupancyGrid, this, _1),
Expand Down Expand Up @@ -239,7 +239,7 @@ void BehaviorVelocityPlannerNode::on_predicted_objects(
planner_data_.predicted_objects = msg;
}

void BehaviorVelocityPlannerNode::onNoGroundPointCloud(
void BehaviorVelocityPlannerNode::on_no_ground_point_cloud(
const sensor_msgs::msg::PointCloud2::ConstSharedPtr msg)
{
geometry_msgs::msg::TransformStamped transform;
Expand Down Expand Up @@ -365,7 +365,7 @@ void BehaviorVelocityPlannerNode::onExternalVelocityLimit(const VelocityLimit::C
planner_data_.external_velocity_limit = *msg;
}

void BehaviorVelocityPlannerNode::onVirtualTrafficLightStates(
void BehaviorVelocityPlannerNode::on_virtual_traffic_light_states(
const tier4_v2x_msgs::msg::VirtualTrafficLightStateArray::ConstSharedPtr msg)
{
std::lock_guard<std::mutex> lock(mutex_);
Expand Down
4 changes: 2 additions & 2 deletions planning/behavior_velocity_planner/src/node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -82,13 +82,13 @@ class BehaviorVelocityPlannerNode : public rclcpp::Node
const autoware_auto_planning_msgs::msg::PathWithLaneId::ConstSharedPtr input_path_msg);
void on_predicted_objects(
const autoware_auto_perception_msgs::msg::PredictedObjects::ConstSharedPtr msg);
void onNoGroundPointCloud(const sensor_msgs::msg::PointCloud2::ConstSharedPtr msg);
void on_no_ground_point_cloud(const sensor_msgs::msg::PointCloud2::ConstSharedPtr msg);
void onOdometry(const nav_msgs::msg::Odometry::ConstSharedPtr msg);
void onAcceleration(const geometry_msgs::msg::AccelWithCovarianceStamped::ConstSharedPtr msg);
void onLaneletMap(const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr msg);
void onTrafficSignals(
const autoware_perception_msgs::msg::TrafficSignalArray::ConstSharedPtr msg);
void onVirtualTrafficLightStates(
void on_virtual_traffic_light_states(
const tier4_v2x_msgs::msg::VirtualTrafficLightStateArray::ConstSharedPtr msg);
void onOccupancyGrid(const nav_msgs::msg::OccupancyGrid::ConstSharedPtr msg);
void onExternalVelocityLimit(const VelocityLimit::ConstSharedPtr msg);
Expand Down

0 comments on commit db1803b

Please sign in to comment.