diff --git a/planning/behavior_velocity_planner/src/node.cpp b/planning/behavior_velocity_planner/src/node.cpp index 2eb60e34073ae..628811b5fff6a 100644 --- a/planning/behavior_velocity_planner/src/node.cpp +++ b/planning/behavior_velocity_planner/src/node.cpp @@ -180,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; @@ -476,7 +476,7 @@ void BehaviorVelocityPlannerNode::publishDebugMarker( } debug_viz_pub_->publish(output_msg); } -} // namespace autoware +} // namespace autoware::behavior_velocity_planner #include RCLCPP_COMPONENTS_REGISTER_NODE(autoware::behavior_velocity_planner::BehaviorVelocityPlannerNode) diff --git a/planning/behavior_velocity_planner/src/node.hpp b/planning/behavior_velocity_planner/src/node.hpp index 55c2b2a4f4619..b343a3ee5afc9 100644 --- a/planning/behavior_velocity_planner/src/node.hpp +++ b/planning/behavior_velocity_planner/src/node.hpp @@ -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); diff --git a/planning/behavior_velocity_planner/src/planner_manager.cpp b/planning/behavior_velocity_planner/src/planner_manager.cpp index bb98a3c1efd72..ba2855d1a39b3 100644 --- a/planning/behavior_velocity_planner/src/planner_manager.cpp +++ b/planning/behavior_velocity_planner/src/planner_manager.cpp @@ -35,7 +35,7 @@ std::string json_dumps_pose(const geometry_msgs::msg::Pose & pose) } diagnostic_msgs::msg::DiagnosticStatus make_stop_reason_diag( - const std::string& stop_reason, const geometry_msgs::msg::Pose & stop_pose) + 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; @@ -83,7 +83,7 @@ void BehaviorVelocityPlannerManager::removeScenePlugin( { auto it = std::remove_if( scene_manager_plugins_.begin(), scene_manager_plugins_.end(), - [&](const std::shared_ptr& plugin) { + [&](const std::shared_ptr & plugin) { return plugin->getModuleName() == name; }); @@ -129,4 +129,4 @@ diagnostic_msgs::msg::DiagnosticStatus BehaviorVelocityPlannerManager::getStopRe { return stop_reason_diag_; } -} // namespace autoware +} // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_planner/test/src/test_node_interface.cpp b/planning/behavior_velocity_planner/test/src/test_node_interface.cpp index 120230694ae97..1dde859395853 100644 --- a/planning/behavior_velocity_planner/test/src/test_node_interface.cpp +++ b/planning/behavior_velocity_planner/test/src/test_node_interface.cpp @@ -115,8 +115,8 @@ std::shared_ptr generate_node() } void publish_mandatory_topics( - const std::shared_ptr& test_manager, - const std::shared_ptr& test_target_node) + const std::shared_ptr & test_manager, + const std::shared_ptr & test_target_node) { // publish necessary topics from test_manager test_manager->publishTF(test_target_node, "/tf");