Skip to content

Commit

Permalink
fix(autoware_behavior_velocity_planner): fix clang-tidy 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 10, 2024
1 parent b230ccd commit dedadc4
Show file tree
Hide file tree
Showing 4 changed files with 37 additions and 43 deletions.
29 changes: 13 additions & 16 deletions planning/behavior_velocity_planner/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@

namespace
{
rclcpp::SubscriptionOptions createSubscriptionOptions(rclcpp::Node * node_ptr)
rclcpp::SubscriptionOptions create_subscription_options(rclcpp::Node * node_ptr)
{
rclcpp::CallbackGroup::SharedPtr callback_group =
node_ptr->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
Expand All @@ -52,9 +52,7 @@ rclcpp::SubscriptionOptions createSubscriptionOptions(rclcpp::Node * node_ptr)
}
} // namespace

namespace autoware
{
namespace behavior_velocity_planner
namespace autoware::behavior_velocity_planner
{
namespace
{
Expand Down Expand Up @@ -83,44 +81,44 @@ BehaviorVelocityPlannerNode::BehaviorVelocityPlannerNode(const rclcpp::NodeOptio
trigger_sub_path_with_lane_id_ =
this->create_subscription<autoware_auto_planning_msgs::msg::PathWithLaneId>(
"~/input/path_with_lane_id", 1, std::bind(&BehaviorVelocityPlannerNode::onTrigger, this, _1),
createSubscriptionOptions(this));
create_subscription_options(this));

// Subscribers
sub_predicted_objects_ =
this->create_subscription<autoware_auto_perception_msgs::msg::PredictedObjects>(
"~/input/dynamic_objects", 1,
std::bind(&BehaviorVelocityPlannerNode::onPredictedObjects, this, _1),
createSubscriptionOptions(this));
create_subscription_options(this));
sub_no_ground_pointcloud_ = this->create_subscription<sensor_msgs::msg::PointCloud2>(
"~/input/no_ground_pointcloud", rclcpp::SensorDataQoS(),
std::bind(&BehaviorVelocityPlannerNode::onNoGroundPointCloud, this, _1),
createSubscriptionOptions(this));
create_subscription_options(this));
sub_vehicle_odometry_ = this->create_subscription<nav_msgs::msg::Odometry>(
"~/input/vehicle_odometry", 1, std::bind(&BehaviorVelocityPlannerNode::onOdometry, this, _1),
createSubscriptionOptions(this));
create_subscription_options(this));
sub_acceleration_ = this->create_subscription<geometry_msgs::msg::AccelWithCovarianceStamped>(
"~/input/accel", 1, std::bind(&BehaviorVelocityPlannerNode::onAcceleration, this, _1),
createSubscriptionOptions(this));
create_subscription_options(this));
sub_lanelet_map_ = this->create_subscription<autoware_auto_mapping_msgs::msg::HADMapBin>(
"~/input/vector_map", rclcpp::QoS(10).transient_local(),
std::bind(&BehaviorVelocityPlannerNode::onLaneletMap, this, _1),
createSubscriptionOptions(this));
create_subscription_options(this));
sub_traffic_signals_ =
this->create_subscription<autoware_perception_msgs::msg::TrafficSignalArray>(
"~/input/traffic_signals", 1,
std::bind(&BehaviorVelocityPlannerNode::onTrafficSignals, this, _1),
createSubscriptionOptions(this));
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));
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),
createSubscriptionOptions(this));
create_subscription_options(this));
sub_occupancy_grid_ = this->create_subscription<nav_msgs::msg::OccupancyGrid>(
"~/input/occupancy_grid", 1, std::bind(&BehaviorVelocityPlannerNode::onOccupancyGrid, this, _1),
createSubscriptionOptions(this));
create_subscription_options(this));

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

// NOTE: argument planner_data must not be referenced for multithreading
bool BehaviorVelocityPlannerNode::isDataReady(
const PlannerData planner_data, rclcpp::Clock clock) const
const PlannerData& planner_data, rclcpp::Clock clock) const
{
const auto & d = planner_data;

Expand Down Expand Up @@ -478,7 +476,6 @@ void BehaviorVelocityPlannerNode::publishDebugMarker(
}
debug_viz_pub_->publish(output_msg);
}
} // namespace behavior_velocity_planner
} // namespace autoware

#include <rclcpp_components/register_node_macro.hpp>
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 @@ -114,7 +114,7 @@ class BehaviorVelocityPlannerNode : public rclcpp::Node
BehaviorVelocityPlannerManager planner_manager_;
bool is_driving_forward_{true};
HADMapBin::ConstSharedPtr map_ptr_{nullptr};
bool has_received_map_;
bool has_received_map_{};

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

// function
geometry_msgs::msg::PoseStamped getCurrentPose();
bool isDataReady(const PlannerData planner_data, rclcpp::Clock clock) const;
bool isDataReady(const PlannerData& planner_data, rclcpp::Clock clock) const;
autoware_auto_planning_msgs::msg::Path generatePath(
const autoware_auto_planning_msgs::msg::PathWithLaneId::ConstSharedPtr input_path_msg,
const PlannerData & planner_data);
Expand Down
25 changes: 11 additions & 14 deletions planning/behavior_velocity_planner/src/planner_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,13 +19,11 @@
#include <memory>
#include <string>

namespace autoware
{
namespace behavior_velocity_planner
namespace autoware::behavior_velocity_planner
{
namespace
{
std::string jsonDumpsPose(const geometry_msgs::msg::Pose & pose)
std::string json_dumps_pose(const geometry_msgs::msg::Pose & pose)
{
const std::string json_dumps_pose =
(boost::format(
Expand All @@ -36,16 +34,16 @@ std::string jsonDumpsPose(const geometry_msgs::msg::Pose & pose)
return json_dumps_pose;
}

diagnostic_msgs::msg::DiagnosticStatus makeStopReasonDiag(
const std::string stop_reason, const geometry_msgs::msg::Pose & stop_pose)
diagnostic_msgs::msg::DiagnosticStatus make_stop_reason_diag(
const std::string& stop_reason, const geometry_msgs::msg::Pose & stop_pose)
{
diagnostic_msgs::msg::DiagnosticStatus stop_reason_diag;
diagnostic_msgs::msg::KeyValue stop_reason_diag_kv;
stop_reason_diag.level = diagnostic_msgs::msg::DiagnosticStatus::OK;
stop_reason_diag.name = "stop_reason";
stop_reason_diag.message = stop_reason;
stop_reason_diag_kv.key = "stop_pose";
stop_reason_diag_kv.value = jsonDumpsPose(stop_pose);
stop_reason_diag_kv.value = json_dumps_pose(stop_pose);
stop_reason_diag.values.push_back(stop_reason_diag_kv);
return stop_reason_diag;
}
Expand Down Expand Up @@ -85,7 +83,7 @@ void BehaviorVelocityPlannerManager::removeScenePlugin(
{
auto it = std::remove_if(
scene_manager_plugins_.begin(), scene_manager_plugins_.end(),
[&](const std::shared_ptr<autoware::behavior_velocity_planner::PluginInterface> plugin) {
[&](const std::shared_ptr<autoware::behavior_velocity_planner::PluginInterface>& plugin) {
return plugin->getModuleName() == name;
});

Expand All @@ -111,17 +109,17 @@ autoware_auto_planning_msgs::msg::PathWithLaneId BehaviorVelocityPlannerManager:
for (const auto & plugin : scene_manager_plugins_) {
plugin->updateSceneModuleInstances(planner_data, input_path_msg);
plugin->plan(&output_path_msg);
const auto firstStopPathPointIndex = plugin->getFirstStopPathPointIndex();
const auto first_stop_path_point_index = plugin->getFirstStopPathPointIndex();

if (firstStopPathPointIndex) {
if (firstStopPathPointIndex.value() < first_stop_path_point_index) {
first_stop_path_point_index = firstStopPathPointIndex.value();
if (first_stop_path_point_index) {
if (first_stop_path_point_index.value() < first_stop_path_point_index) {
first_stop_path_point_index = first_stop_path_point_index.value();
stop_reason_msg = plugin->getModuleName();
}
}
}

stop_reason_diag_ = makeStopReasonDiag(
stop_reason_diag_ = make_stop_reason_diag(
stop_reason_msg, output_path_msg.points[first_stop_path_point_index].point.pose);

return output_path_msg;
Expand All @@ -131,5 +129,4 @@ diagnostic_msgs::msg::DiagnosticStatus BehaviorVelocityPlannerManager::getStopRe
{
return stop_reason_diag_;
}
} // namespace behavior_velocity_planner
} // namespace autoware
22 changes: 11 additions & 11 deletions planning/behavior_velocity_planner/test/src/test_node_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@
using autoware::behavior_velocity_planner::BehaviorVelocityPlannerNode;
using planning_test_utils::PlanningInterfaceTestManager;

std::shared_ptr<PlanningInterfaceTestManager> generateTestManager()
std::shared_ptr<PlanningInterfaceTestManager> generate_test_manager()
{
auto test_manager = std::make_shared<PlanningInterfaceTestManager>();

Expand All @@ -43,7 +43,7 @@ std::shared_ptr<PlanningInterfaceTestManager> generateTestManager()
return test_manager;
}

std::shared_ptr<BehaviorVelocityPlannerNode> generateNode()
std::shared_ptr<BehaviorVelocityPlannerNode> generate_node()
{
auto node_options = rclcpp::NodeOptions{};

Expand Down Expand Up @@ -114,9 +114,9 @@ std::shared_ptr<BehaviorVelocityPlannerNode> generateNode()
return std::make_shared<BehaviorVelocityPlannerNode>(node_options);
}

void publishMandatoryTopics(
std::shared_ptr<PlanningInterfaceTestManager> test_manager,
std::shared_ptr<BehaviorVelocityPlannerNode> test_target_node)
void publish_mandatory_topics(
const std::shared_ptr<PlanningInterfaceTestManager>& test_manager,
const std::shared_ptr<BehaviorVelocityPlannerNode>& test_target_node)
{
// publish necessary topics from test_manager
test_manager->publishTF(test_target_node, "/tf");
Expand All @@ -142,10 +142,10 @@ void publishMandatoryTopics(
TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionPathWithLaneID)
{
rclcpp::init(0, nullptr);
auto test_manager = generateTestManager();
auto test_target_node = generateNode();
auto test_manager = generate_test_manager();
auto test_target_node = generate_node();

publishMandatoryTopics(test_manager, test_target_node);
publish_mandatory_topics(test_manager, test_target_node);

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

auto test_manager = generateTestManager();
auto test_target_node = generateNode();
publishMandatoryTopics(test_manager, test_target_node);
auto test_manager = generate_test_manager();
auto test_target_node = generate_node();
publish_mandatory_topics(test_manager, test_target_node);

// test for normal trajectory
ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPathWithLaneId(test_target_node));
Expand Down

0 comments on commit dedadc4

Please sign in to comment.