Skip to content

Commit 0e7be0c

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

File tree

2 files changed

+25
-25
lines changed

2 files changed

+25
-25
lines changed

planning/behavior_velocity_planner/src/node.cpp

+20-20
Original file line numberDiff line numberDiff line change
@@ -40,7 +40,7 @@
4040

4141
namespace
4242
{
43-
rclcpp::SubscriptionOptions createSubscriptionOptions(rclcpp::Node * node_ptr)
43+
rclcpp::SubscriptionOptions create_subscription_options(rclcpp::Node * node_ptr)
4444
{
4545
rclcpp::CallbackGroup::SharedPtr callback_group =
4646
node_ptr->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
@@ -83,44 +83,44 @@ BehaviorVelocityPlannerNode::BehaviorVelocityPlannerNode(const rclcpp::NodeOptio
8383
trigger_sub_path_with_lane_id_ =
8484
this->create_subscription<autoware_auto_planning_msgs::msg::PathWithLaneId>(
8585
"~/input/path_with_lane_id", 1, std::bind(&BehaviorVelocityPlannerNode::on_trigger, this, _1),
86-
createSubscriptionOptions(this));
86+
create_subscription_options(this));
8787

8888
// Subscribers
8989
sub_predicted_objects_ =
9090
this->create_subscription<autoware_auto_perception_msgs::msg::PredictedObjects>(
9191
"~/input/dynamic_objects", 1,
9292
std::bind(&BehaviorVelocityPlannerNode::on_predicted_objects, this, _1),
93-
createSubscriptionOptions(this));
93+
create_subscription_options(this));
9494
sub_no_ground_pointcloud_ = this->create_subscription<sensor_msgs::msg::PointCloud2>(
9595
"~/input/no_ground_pointcloud", rclcpp::SensorDataQoS(),
9696
std::bind(&BehaviorVelocityPlannerNode::on_no_ground_point_cloud, this, _1),
97-
createSubscriptionOptions(this));
97+
create_subscription_options(this));
9898
sub_vehicle_odometry_ = this->create_subscription<nav_msgs::msg::Odometry>(
99-
"~/input/vehicle_odometry", 1, std::bind(&BehaviorVelocityPlannerNode::onOdometry, this, _1),
100-
createSubscriptionOptions(this));
99+
"~/input/vehicle_odometry", 1, std::bind(&BehaviorVelocityPlannerNode::on_odometry, this, _1),
100+
create_subscription_options(this));
101101
sub_acceleration_ = this->create_subscription<geometry_msgs::msg::AccelWithCovarianceStamped>(
102-
"~/input/accel", 1, std::bind(&BehaviorVelocityPlannerNode::onAcceleration, this, _1),
103-
createSubscriptionOptions(this));
102+
"~/input/accel", 1, std::bind(&BehaviorVelocityPlannerNode::on_acceleration, this, _1),
103+
create_subscription_options(this));
104104
sub_lanelet_map_ = this->create_subscription<autoware_auto_mapping_msgs::msg::HADMapBin>(
105105
"~/input/vector_map", rclcpp::QoS(10).transient_local(),
106-
std::bind(&BehaviorVelocityPlannerNode::onLaneletMap, this, _1),
107-
createSubscriptionOptions(this));
106+
std::bind(&BehaviorVelocityPlannerNode::on_lanelet_map, this, _1),
107+
create_subscription_options(this));
108108
sub_traffic_signals_ =
109109
this->create_subscription<autoware_perception_msgs::msg::TrafficSignalArray>(
110110
"~/input/traffic_signals", 1,
111111
std::bind(&BehaviorVelocityPlannerNode::onTrafficSignals, this, _1),
112-
createSubscriptionOptions(this));
112+
create_subscription_options(this));
113113
sub_external_velocity_limit_ = this->create_subscription<VelocityLimit>(
114114
"~/input/external_velocity_limit_mps", rclcpp::QoS{1}.transient_local(),
115115
std::bind(&BehaviorVelocityPlannerNode::onExternalVelocityLimit, this, _1));
116116
sub_virtual_traffic_light_states_ =
117117
this->create_subscription<tier4_v2x_msgs::msg::VirtualTrafficLightStateArray>(
118118
"~/input/virtual_traffic_light_states", 1,
119119
std::bind(&BehaviorVelocityPlannerNode::on_virtual_traffic_light_states, this, _1),
120-
createSubscriptionOptions(this));
120+
create_subscription_options(this));
121121
sub_occupancy_grid_ = this->create_subscription<nav_msgs::msg::OccupancyGrid>(
122-
"~/input/occupancy_grid", 1, std::bind(&BehaviorVelocityPlannerNode::onOccupancyGrid, this, _1),
123-
createSubscriptionOptions(this));
122+
"~/input/occupancy_grid", 1, std::bind(&BehaviorVelocityPlannerNode::on_occupancy_grid, this, _1),
123+
create_subscription_options(this));
124124

125125
srv_load_plugin_ = create_service<LoadPlugin>(
126126
"~/service/load_plugin", std::bind(&BehaviorVelocityPlannerNode::onLoadPlugin, this, _1, _2));
@@ -181,7 +181,7 @@ void BehaviorVelocityPlannerNode::onUnloadPlugin(
181181
}
182182

183183
// NOTE: argument planner_data must not be referenced for multithreading
184-
bool BehaviorVelocityPlannerNode::isDataReady(
184+
bool BehaviorVelocityPlannerNode::is_data_ready(
185185
const PlannerData & planner_data, rclcpp::Clock clock) const
186186
{
187187
const auto & d = planner_data;
@@ -225,7 +225,7 @@ bool BehaviorVelocityPlannerNode::isDataReady(
225225
return true;
226226
}
227227

228-
void BehaviorVelocityPlannerNode::onOccupancyGrid(
228+
void BehaviorVelocityPlannerNode::on_occupancy_grid(
229229
const nav_msgs::msg::OccupancyGrid::ConstSharedPtr msg)
230230
{
231231
std::lock_guard<std::mutex> lock(mutex_);
@@ -266,7 +266,7 @@ void BehaviorVelocityPlannerNode::on_no_ground_point_cloud(
266266
}
267267
}
268268

269-
void BehaviorVelocityPlannerNode::onOdometry(const nav_msgs::msg::Odometry::ConstSharedPtr msg)
269+
void BehaviorVelocityPlannerNode::on_odometry(const nav_msgs::msg::Odometry::ConstSharedPtr msg)
270270
{
271271
std::lock_guard<std::mutex> lock(mutex_);
272272

@@ -299,7 +299,7 @@ void BehaviorVelocityPlannerNode::onOdometry(const nav_msgs::msg::Odometry::Cons
299299
}
300300
}
301301

302-
void BehaviorVelocityPlannerNode::onAcceleration(
302+
void BehaviorVelocityPlannerNode::on_acceleration(
303303
const geometry_msgs::msg::AccelWithCovarianceStamped::ConstSharedPtr msg)
304304
{
305305
std::lock_guard<std::mutex> lock(mutex_);
@@ -315,7 +315,7 @@ void BehaviorVelocityPlannerNode::onParam()
315315
std::make_unique<motion_velocity_smoother::AnalyticalJerkConstrainedSmoother>(*this);
316316
}
317317

318-
void BehaviorVelocityPlannerNode::onLaneletMap(
318+
void BehaviorVelocityPlannerNode::on_lanelet_map(
319319
const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr msg)
320320
{
321321
std::lock_guard<std::mutex> lock(mutex_);
@@ -377,7 +377,7 @@ void BehaviorVelocityPlannerNode::on_trigger(
377377
{
378378
std::unique_lock<std::mutex> lk(mutex_);
379379

380-
if (!isDataReady(planner_data_, *get_clock())) {
380+
if (!is_data_ready(planner_data_, *get_clock())) {
381381
return;
382382
}
383383

planning/behavior_velocity_planner/src/node.hpp

+5-5
Original file line numberDiff line numberDiff line change
@@ -83,14 +83,14 @@ class BehaviorVelocityPlannerNode : public rclcpp::Node
8383
void on_predicted_objects(
8484
const autoware_auto_perception_msgs::msg::PredictedObjects::ConstSharedPtr msg);
8585
void on_no_ground_point_cloud(const sensor_msgs::msg::PointCloud2::ConstSharedPtr msg);
86-
void onOdometry(const nav_msgs::msg::Odometry::ConstSharedPtr msg);
87-
void onAcceleration(const geometry_msgs::msg::AccelWithCovarianceStamped::ConstSharedPtr msg);
88-
void onLaneletMap(const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr msg);
86+
void on_odometry(const nav_msgs::msg::Odometry::ConstSharedPtr msg);
87+
void on_acceleration(const geometry_msgs::msg::AccelWithCovarianceStamped::ConstSharedPtr msg);
88+
void on_lanelet_map(const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr msg);
8989
void onTrafficSignals(
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);
93-
void onOccupancyGrid(const nav_msgs::msg::OccupancyGrid::ConstSharedPtr msg);
93+
void on_occupancy_grid(const nav_msgs::msg::OccupancyGrid::ConstSharedPtr msg);
9494
void onExternalVelocityLimit(const VelocityLimit::ConstSharedPtr msg);
9595
void onParam();
9696

@@ -126,7 +126,7 @@ class BehaviorVelocityPlannerNode : public rclcpp::Node
126126

127127
// function
128128
geometry_msgs::msg::PoseStamped getCurrentPose();
129-
bool isDataReady(const PlannerData & planner_data, rclcpp::Clock clock) const;
129+
bool is_data_ready(const PlannerData & planner_data, rclcpp::Clock clock) const;
130130
autoware_auto_planning_msgs::msg::Path generatePath(
131131
const autoware_auto_planning_msgs::msg::PathWithLaneId::ConstSharedPtr input_path_msg,
132132
const PlannerData & planner_data);

0 commit comments

Comments
 (0)