Skip to content

Commit 1bf094a

Browse files
committed
fix(autoware_behavior_velocity_planner): fix build errors
Signed-off-by: Esteve Fernandez <esteve.fernandez@tier4.jp>
1 parent 7c3c3d6 commit 1bf094a

File tree

4 files changed

+40
-41
lines changed

4 files changed

+40
-41
lines changed

planning/behavior_velocity_planner/src/node.cpp

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

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

8686
// Subscribers
8787
sub_predicted_objects_ =
8888
this->create_subscription<autoware_auto_perception_msgs::msg::PredictedObjects>(
8989
"~/input/dynamic_objects", 1,
9090
std::bind(&BehaviorVelocityPlannerNode::onPredictedObjects, this, _1),
91-
create_subscription_options(this));
91+
createSubscriptionOptions(this));
9292
sub_no_ground_pointcloud_ = this->create_subscription<sensor_msgs::msg::PointCloud2>(
9393
"~/input/no_ground_pointcloud", rclcpp::SensorDataQoS(),
9494
std::bind(&BehaviorVelocityPlannerNode::onNoGroundPointCloud, this, _1),
95-
create_subscription_options(this));
95+
createSubscriptionOptions(this));
9696
sub_vehicle_odometry_ = this->create_subscription<nav_msgs::msg::Odometry>(
9797
"~/input/vehicle_odometry", 1, std::bind(&BehaviorVelocityPlannerNode::onOdometry, this, _1),
98-
create_subscription_options(this));
98+
createSubscriptionOptions(this));
9999
sub_acceleration_ = this->create_subscription<geometry_msgs::msg::AccelWithCovarianceStamped>(
100100
"~/input/accel", 1, std::bind(&BehaviorVelocityPlannerNode::onAcceleration, this, _1),
101-
create_subscription_options(this));
101+
createSubscriptionOptions(this));
102102
sub_lanelet_map_ = this->create_subscription<autoware_auto_mapping_msgs::msg::HADMapBin>(
103103
"~/input/vector_map", rclcpp::QoS(10).transient_local(),
104104
std::bind(&BehaviorVelocityPlannerNode::onLaneletMap, this, _1),
105-
create_subscription_options(this));
105+
createSubscriptionOptions(this));
106106
sub_traffic_signals_ =
107107
this->create_subscription<autoware_perception_msgs::msg::TrafficSignalArray>(
108108
"~/input/traffic_signals", 1,
109109
std::bind(&BehaviorVelocityPlannerNode::onTrafficSignals, this, _1),
110-
create_subscription_options(this));
110+
createSubscriptionOptions(this));
111111
sub_external_velocity_limit_ = this->create_subscription<VelocityLimit>(
112112
"~/input/external_velocity_limit_mps", rclcpp::QoS{1}.transient_local(),
113113
std::bind(&BehaviorVelocityPlannerNode::onExternalVelocityLimit, this, _1));
114114
sub_virtual_traffic_light_states_ =
115115
this->create_subscription<tier4_v2x_msgs::msg::VirtualTrafficLightStateArray>(
116116
"~/input/virtual_traffic_light_states", 1,
117117
std::bind(&BehaviorVelocityPlannerNode::onVirtualTrafficLightStates, this, _1),
118-
create_subscription_options(this));
118+
createSubscriptionOptions(this));
119119
sub_occupancy_grid_ = this->create_subscription<nav_msgs::msg::OccupancyGrid>(
120120
"~/input/occupancy_grid", 1, std::bind(&BehaviorVelocityPlannerNode::onOccupancyGrid, this, _1),
121-
create_subscription_options(this));
121+
createSubscriptionOptions(this));
122122

123123
srv_load_plugin_ = create_service<LoadPlugin>(
124124
"~/service/load_plugin", std::bind(&BehaviorVelocityPlannerNode::onLoadPlugin, this, _1, _2));
@@ -152,7 +152,7 @@ BehaviorVelocityPlannerNode::BehaviorVelocityPlannerNode(const rclcpp::NodeOptio
152152
// Initialize PlannerManager
153153
for (const auto & name : declare_parameter<std::vector<std::string>>("launch_modules")) {
154154
// workaround: Since ROS 2 can't get empty list, launcher set [''] on the parameter.
155-
if (name.empty()) {
155+
if (name == "") {
156156
break;
157157
}
158158
planner_manager_.launchScenePlugin(*this, name);
@@ -180,7 +180,7 @@ void BehaviorVelocityPlannerNode::onUnloadPlugin(
180180

181181
// NOTE: argument planner_data must not be referenced for multithreading
182182
bool BehaviorVelocityPlannerNode::isDataReady(
183-
const PlannerData & planner_data, rclcpp::Clock clock) const
183+
const PlannerData planner_data, rclcpp::Clock clock) const
184184
{
185185
const auto & d = planner_data;
186186

@@ -434,12 +434,11 @@ autoware_auto_planning_msgs::msg::Path BehaviorVelocityPlannerNode::generatePath
434434
std::make_shared<const PlannerData>(planner_data), *input_path_msg);
435435

436436
// screening
437-
const auto filtered_path =
438-
::behavior_velocity_planner::filterLitterPathPoint(to_path(velocity_planned_path));
437+
const auto filtered_path = ::behavior_velocity_planner::filterLitterPathPoint(to_path(velocity_planned_path));
439438

440439
// interpolation
441-
const auto interpolated_path_msg = ::behavior_velocity_planner::interpolatePath(
442-
filtered_path, forward_path_length_, behavior_output_path_interval_);
440+
const auto interpolated_path_msg =
441+
::behavior_velocity_planner::interpolatePath(filtered_path, forward_path_length_, behavior_output_path_interval_);
443442

444443
// check stop point
445444
output_path_msg = ::behavior_velocity_planner::filterStopPathPoint(interpolated_path_msg);

planning/behavior_velocity_planner/src/node.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -114,7 +114,7 @@ class BehaviorVelocityPlannerNode : public rclcpp::Node
114114
BehaviorVelocityPlannerManager planner_manager_;
115115
bool is_driving_forward_{true};
116116
HADMapBin::ConstSharedPtr map_ptr_{nullptr};
117-
bool has_received_map_{};
117+
bool has_received_map_;
118118

119119
rclcpp::Service<LoadPlugin>::SharedPtr srv_load_plugin_;
120120
rclcpp::Service<UnloadPlugin>::SharedPtr srv_unload_plugin_;
@@ -129,7 +129,7 @@ class BehaviorVelocityPlannerNode : public rclcpp::Node
129129

130130
// function
131131
geometry_msgs::msg::PoseStamped getCurrentPose();
132-
bool isDataReady(const PlannerData & planner_data, rclcpp::Clock clock) const;
132+
bool isDataReady(const PlannerData planner_data, rclcpp::Clock clock) const;
133133
autoware_auto_planning_msgs::msg::Path generatePath(
134134
const autoware_auto_planning_msgs::msg::PathWithLaneId::ConstSharedPtr input_path_msg,
135135
const PlannerData & planner_data);

planning/behavior_velocity_planner/src/planner_manager.cpp

+12-12
Original file line numberDiff line numberDiff line change
@@ -23,27 +23,27 @@ namespace autoware::behavior_velocity_planner
2323
{
2424
namespace
2525
{
26-
std::string json_dumps_pose(const geometry_msgs::msg::Pose & pose)
26+
std::string jsonDumpsPose(const geometry_msgs::msg::Pose & pose)
2727
{
28-
const std::string json_dumps_pose =
28+
const std::string jsonDumpsPose =
2929
(boost::format(
3030
R"({"position":{"x":%lf,"y":%lf,"z":%lf},"orientation":{"w":%lf,"x":%lf,"y":%lf,"z":%lf}})") %
3131
pose.position.x % pose.position.y % pose.position.z % pose.orientation.w % pose.orientation.x %
3232
pose.orientation.y % pose.orientation.z)
3333
.str();
34-
return json_dumps_pose;
34+
return jsonDumpsPose;
3535
}
3636

37-
diagnostic_msgs::msg::DiagnosticStatus make_stop_reason_diag(
38-
const std::string & stop_reason, const geometry_msgs::msg::Pose & stop_pose)
37+
diagnostic_msgs::msg::DiagnosticStatus makeStopReasonDiag(
38+
const std::string stop_reason, const geometry_msgs::msg::Pose & stop_pose)
3939
{
4040
diagnostic_msgs::msg::DiagnosticStatus stop_reason_diag;
4141
diagnostic_msgs::msg::KeyValue stop_reason_diag_kv;
4242
stop_reason_diag.level = diagnostic_msgs::msg::DiagnosticStatus::OK;
4343
stop_reason_diag.name = "stop_reason";
4444
stop_reason_diag.message = stop_reason;
4545
stop_reason_diag_kv.key = "stop_pose";
46-
stop_reason_diag_kv.value = json_dumps_pose(stop_pose);
46+
stop_reason_diag_kv.value = jsonDumpsPose(stop_pose);
4747
stop_reason_diag.values.push_back(stop_reason_diag_kv);
4848
return stop_reason_diag;
4949
}
@@ -83,7 +83,7 @@ void BehaviorVelocityPlannerManager::removeScenePlugin(
8383
{
8484
auto it = std::remove_if(
8585
scene_manager_plugins_.begin(), scene_manager_plugins_.end(),
86-
[&](const std::shared_ptr<autoware::behavior_velocity_planner::PluginInterface> & plugin) {
86+
[&](const std::shared_ptr<autoware::behavior_velocity_planner::PluginInterface> plugin) {
8787
return plugin->getModuleName() == name;
8888
});
8989

@@ -109,17 +109,17 @@ autoware_auto_planning_msgs::msg::PathWithLaneId BehaviorVelocityPlannerManager:
109109
for (const auto & plugin : scene_manager_plugins_) {
110110
plugin->updateSceneModuleInstances(planner_data, input_path_msg);
111111
plugin->plan(&output_path_msg);
112-
const auto first_stop_path_point_index = plugin->getFirstStopPathPointIndex();
112+
const auto firstStopPathPointIndex = plugin->getFirstStopPathPointIndex();
113113

114-
if (first_stop_path_point_index) {
115-
if (first_stop_path_point_index.value() < first_stop_path_point_index) {
116-
first_stop_path_point_index = first_stop_path_point_index.value();
114+
if (firstStopPathPointIndex) {
115+
if (firstStopPathPointIndex.value() < first_stop_path_point_index) {
116+
first_stop_path_point_index = firstStopPathPointIndex.value();
117117
stop_reason_msg = plugin->getModuleName();
118118
}
119119
}
120120
}
121121

122-
stop_reason_diag_ = make_stop_reason_diag(
122+
stop_reason_diag_ = makeStopReasonDiag(
123123
stop_reason_msg, output_path_msg.points[first_stop_path_point_index].point.pose);
124124

125125
return output_path_msg;

planning/behavior_velocity_planner/test/src/test_node_interface.cpp

+11-11
Original file line numberDiff line numberDiff line change
@@ -26,7 +26,7 @@
2626
using autoware::behavior_velocity_planner::BehaviorVelocityPlannerNode;
2727
using planning_test_utils::PlanningInterfaceTestManager;
2828

29-
std::shared_ptr<PlanningInterfaceTestManager> generate_test_manager()
29+
std::shared_ptr<PlanningInterfaceTestManager> generateTestManager()
3030
{
3131
auto test_manager = std::make_shared<PlanningInterfaceTestManager>();
3232

@@ -43,7 +43,7 @@ std::shared_ptr<PlanningInterfaceTestManager> generate_test_manager()
4343
return test_manager;
4444
}
4545

46-
std::shared_ptr<BehaviorVelocityPlannerNode> generate_node()
46+
std::shared_ptr<BehaviorVelocityPlannerNode> generateNode()
4747
{
4848
auto node_options = rclcpp::NodeOptions{};
4949

@@ -114,9 +114,9 @@ std::shared_ptr<BehaviorVelocityPlannerNode> generate_node()
114114
return std::make_shared<BehaviorVelocityPlannerNode>(node_options);
115115
}
116116

117-
void publish_mandatory_topics(
118-
const std::shared_ptr<PlanningInterfaceTestManager> & test_manager,
119-
const std::shared_ptr<BehaviorVelocityPlannerNode> & test_target_node)
117+
void publishMandatoryTopics(
118+
std::shared_ptr<PlanningInterfaceTestManager> test_manager,
119+
std::shared_ptr<BehaviorVelocityPlannerNode> test_target_node)
120120
{
121121
// publish necessary topics from test_manager
122122
test_manager->publishTF(test_target_node, "/tf");
@@ -142,10 +142,10 @@ void publish_mandatory_topics(
142142
TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionPathWithLaneID)
143143
{
144144
rclcpp::init(0, nullptr);
145-
auto test_manager = generate_test_manager();
146-
auto test_target_node = generate_node();
145+
auto test_manager = generateTestManager();
146+
auto test_target_node = generateNode();
147147

148-
publish_mandatory_topics(test_manager, test_target_node);
148+
publishMandatoryTopics(test_manager, test_target_node);
149149

150150
// test with nominal path_with_lane_id
151151
ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPathWithLaneId(test_target_node));
@@ -161,9 +161,9 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose)
161161
{
162162
rclcpp::init(0, nullptr);
163163

164-
auto test_manager = generate_test_manager();
165-
auto test_target_node = generate_node();
166-
publish_mandatory_topics(test_manager, test_target_node);
164+
auto test_manager = generateTestManager();
165+
auto test_target_node = generateNode();
166+
publishMandatoryTopics(test_manager, test_target_node);
167167

168168
// test for normal trajectory
169169
ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPathWithLaneId(test_target_node));

0 commit comments

Comments
 (0)