diff --git a/planning/behavior_velocity_planner/src/node.cpp b/planning/behavior_velocity_planner/src/node.cpp index 30dc9daa633b4..9da26637103b1 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; @@ -434,11 +434,12 @@ autoware_auto_planning_msgs::msg::Path BehaviorVelocityPlannerNode::generatePath std::make_shared(planner_data), *input_path_msg); // screening - const auto filtered_path = ::behavior_velocity_planner::filterLitterPathPoint(to_path(velocity_planned_path)); + const auto filtered_path = + ::behavior_velocity_planner::filterLitterPathPoint(to_path(velocity_planned_path)); // interpolation - const auto interpolated_path_msg = - ::behavior_velocity_planner::interpolatePath(filtered_path, forward_path_length_, behavior_output_path_interval_); + const auto interpolated_path_msg = ::behavior_velocity_planner::interpolatePath( + filtered_path, forward_path_length_, behavior_output_path_interval_); // check stop point output_path_msg = ::behavior_velocity_planner::filterStopPathPoint(interpolated_path_msg); diff --git a/planning/behavior_velocity_planner/src/node.hpp b/planning/behavior_velocity_planner/src/node.hpp index 34d6ade19d248..c4d903001cb4f 100644 --- a/planning/behavior_velocity_planner/src/node.hpp +++ b/planning/behavior_velocity_planner/src/node.hpp @@ -136,6 +136,6 @@ class BehaviorVelocityPlannerNode : public rclcpp::Node std::unique_ptr published_time_publisher_; }; -} // namespace autoware +} // namespace autoware::behavior_velocity_planner #endif // NODE_HPP_ diff --git a/planning/behavior_velocity_planner/src/planner_manager.cpp b/planning/behavior_velocity_planner/src/planner_manager.cpp index 9682453540b0b..9d581f8609749 100644 --- a/planning/behavior_velocity_planner/src/planner_manager.cpp +++ b/planning/behavior_velocity_planner/src/planner_manager.cpp @@ -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; }); diff --git a/planning/behavior_velocity_planner/src/planner_manager.hpp b/planning/behavior_velocity_planner/src/planner_manager.hpp index c48294c9c1e63..f9c1d0253de62 100644 --- a/planning/behavior_velocity_planner/src/planner_manager.hpp +++ b/planning/behavior_velocity_planner/src/planner_manager.hpp @@ -59,6 +59,6 @@ class BehaviorVelocityPlannerManager pluginlib::ClassLoader plugin_loader_; std::vector> scene_manager_plugins_; }; -} // namespace autoware +} // namespace autoware::behavior_velocity_planner #endif // PLANNER_MANAGER_HPP_