Skip to content

Commit 2783d6e

Browse files
style(pre-commit): autofix
1 parent 6c0337b commit 2783d6e

File tree

4 files changed

+8
-7
lines changed

4 files changed

+8
-7
lines changed

planning/behavior_velocity_planner/src/node.cpp

+5-4
Original file line numberDiff line numberDiff line change
@@ -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,11 +434,12 @@ 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 = ::behavior_velocity_planner::filterLitterPathPoint(to_path(velocity_planned_path));
437+
const auto filtered_path =
438+
::behavior_velocity_planner::filterLitterPathPoint(to_path(velocity_planned_path));
438439

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

443444
// check stop point
444445
output_path_msg = ::behavior_velocity_planner::filterStopPathPoint(interpolated_path_msg);

planning/behavior_velocity_planner/src/node.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -136,6 +136,6 @@ class BehaviorVelocityPlannerNode : public rclcpp::Node
136136

137137
std::unique_ptr<tier4_autoware_utils::PublishedTimePublisher> published_time_publisher_;
138138
};
139-
} // namespace autoware
139+
} // namespace autoware::behavior_velocity_planner
140140

141141
#endif // NODE_HPP_

planning/behavior_velocity_planner/src/planner_manager.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -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

planning/behavior_velocity_planner/src/planner_manager.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -59,6 +59,6 @@ class BehaviorVelocityPlannerManager
5959
pluginlib::ClassLoader<PluginInterface> plugin_loader_;
6060
std::vector<std::shared_ptr<PluginInterface>> scene_manager_plugins_;
6161
};
62-
} // namespace autoware
62+
} // namespace autoware::behavior_velocity_planner
6363

6464
#endif // PLANNER_MANAGER_HPP_

0 commit comments

Comments
 (0)