Skip to content
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.

Commit 5f398fc

Browse files
pre-commit-ci[bot]xmfcx
authored andcommittedFeb 25, 2025·
style(pre-commit): autofix
1 parent 5743fcb commit 5f398fc

File tree

14 files changed

+29
-34
lines changed

14 files changed

+29
-34
lines changed
 

‎planning/autoware_velocity_smoother/include/autoware/velocity_smoother/node.hpp

+2-3
Original file line numberDiff line numberDiff line change
@@ -61,10 +61,10 @@ namespace autoware::velocity_smoother
6161
using autoware_planning_msgs::msg::Trajectory;
6262
using autoware_planning_msgs::msg::TrajectoryPoint;
6363
using TrajectoryPoints = std::vector<TrajectoryPoint>;
64-
using autoware_utils::DiagnosticsInterface;
6564
using autoware_adapi_v1_msgs::msg::OperationModeState;
6665
using autoware_internal_debug_msgs::msg::Float32Stamped;
6766
using autoware_internal_debug_msgs::msg::Float64Stamped;
67+
using autoware_utils::DiagnosticsInterface;
6868
using geometry_msgs::msg::AccelWithCovarianceStamped;
6969
using geometry_msgs::msg::Pose;
7070
using geometry_msgs::msg::PoseStamped;
@@ -270,8 +270,7 @@ class VelocitySmootherNode : public rclcpp::Node
270270
rclcpp::Publisher<Float32Stamped>::SharedPtr debug_closest_jerk_;
271271
rclcpp::Publisher<Float64Stamped>::SharedPtr debug_calculation_time_;
272272
rclcpp::Publisher<Float32Stamped>::SharedPtr debug_closest_max_velocity_;
273-
rclcpp::Publisher<autoware_utils::ProcessingTimeDetail>::SharedPtr
274-
debug_processing_time_detail_;
273+
rclcpp::Publisher<autoware_utils::ProcessingTimeDetail>::SharedPtr debug_processing_time_detail_;
275274

276275
// For Jerk Filtered Algorithm Debug
277276
rclcpp::Publisher<Trajectory>::SharedPtr pub_forward_filtered_trajectory_;

‎planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -16,9 +16,9 @@
1616
#define AUTOWARE__VELOCITY_SMOOTHER__SMOOTHER__ANALYTICAL_JERK_CONSTRAINED_SMOOTHER__ANALYTICAL_JERK_CONSTRAINED_SMOOTHER_HPP_ // NOLINT
1717

1818
#include "autoware/motion_utils/trajectory/trajectory.hpp"
19-
#include "autoware_utils/system/time_keeper.hpp"
2019
#include "autoware/velocity_smoother/smoother/analytical_jerk_constrained_smoother/velocity_planning_utils.hpp"
2120
#include "autoware/velocity_smoother/smoother/smoother_base.hpp"
21+
#include "autoware_utils/system/time_keeper.hpp"
2222
#include "rclcpp/rclcpp.hpp"
2323
#include "tf2/utils.h"
2424

‎planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/jerk_filtered_smoother.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -17,9 +17,9 @@
1717

1818
#include "autoware/motion_utils/trajectory/trajectory.hpp"
1919
#include "autoware/qp_interface/qp_interface.hpp"
20+
#include "autoware/velocity_smoother/smoother/smoother_base.hpp"
2021
#include "autoware_utils/geometry/geometry.hpp"
2122
#include "autoware_utils/system/time_keeper.hpp"
22-
#include "autoware/velocity_smoother/smoother/smoother_base.hpp"
2323

2424
#include "autoware_planning_msgs/msg/trajectory_point.hpp"
2525

‎planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/l2_pseudo_jerk_smoother.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -17,9 +17,9 @@
1717

1818
#include "autoware/motion_utils/trajectory/trajectory.hpp"
1919
#include "autoware/osqp_interface/osqp_interface.hpp"
20+
#include "autoware/velocity_smoother/smoother/smoother_base.hpp"
2021
#include "autoware_utils/geometry/geometry.hpp"
2122
#include "autoware_utils/system/time_keeper.hpp"
22-
#include "autoware/velocity_smoother/smoother/smoother_base.hpp"
2323

2424
#include "autoware_planning_msgs/msg/trajectory_point.hpp"
2525

‎planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/linf_pseudo_jerk_smoother.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -17,9 +17,9 @@
1717

1818
#include "autoware/motion_utils/trajectory/trajectory.hpp"
1919
#include "autoware/osqp_interface/osqp_interface.hpp"
20+
#include "autoware/velocity_smoother/smoother/smoother_base.hpp"
2021
#include "autoware_utils/geometry/geometry.hpp"
2122
#include "autoware_utils/system/time_keeper.hpp"
22-
#include "autoware/velocity_smoother/smoother/smoother_base.hpp"
2323

2424
#include "autoware_planning_msgs/msg/trajectory_point.hpp"
2525

‎planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/smoother_base.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -15,8 +15,8 @@
1515
#ifndef AUTOWARE__VELOCITY_SMOOTHER__SMOOTHER__SMOOTHER_BASE_HPP_
1616
#define AUTOWARE__VELOCITY_SMOOTHER__SMOOTHER__SMOOTHER_BASE_HPP_
1717

18-
#include "autoware_utils/system/time_keeper.hpp"
1918
#include "autoware/velocity_smoother/resample.hpp"
19+
#include "autoware_utils/system/time_keeper.hpp"
2020
#include "rclcpp/rclcpp.hpp"
2121

2222
#include "autoware_planning_msgs/msg/trajectory_point.hpp"

‎planning/autoware_velocity_smoother/src/node.cpp

+6-9
Original file line numberDiff line numberDiff line change
@@ -15,10 +15,10 @@
1515
#include "autoware/velocity_smoother/node.hpp"
1616

1717
#include "autoware/motion_utils/marker/marker_helper.hpp"
18-
#include "autoware_utils/ros/update_param.hpp"
1918
#include "autoware/velocity_smoother/smoother/jerk_filtered_smoother.hpp"
2019
#include "autoware/velocity_smoother/smoother/l2_pseudo_jerk_smoother.hpp"
2120
#include "autoware/velocity_smoother/smoother/linf_pseudo_jerk_smoother.hpp"
21+
#include "autoware_utils/ros/update_param.hpp"
2222

2323
#include <autoware_vehicle_info_utils/vehicle_info_utils.hpp>
2424

@@ -50,10 +50,9 @@ VelocitySmootherNode::VelocitySmootherNode(const rclcpp::NodeOptions & node_opti
5050

5151
// create time_keeper and its publisher
5252
// NOTE: This has to be called before setupSmoother to pass the time_keeper to the smoother.
53-
debug_processing_time_detail_ = create_publisher<autoware_utils::ProcessingTimeDetail>(
54-
"~/debug/processing_time_detail_ms", 1);
55-
time_keeper_ =
56-
std::make_shared<autoware_utils::TimeKeeper>(debug_processing_time_detail_);
53+
debug_processing_time_detail_ =
54+
create_publisher<autoware_utils::ProcessingTimeDetail>("~/debug/processing_time_detail_ms", 1);
55+
time_keeper_ = std::make_shared<autoware_utils::TimeKeeper>(debug_processing_time_detail_);
5756

5857
// create smoother
5958
setupSmoother(wheelbase_);
@@ -99,8 +98,7 @@ VelocitySmootherNode::VelocitySmootherNode(const rclcpp::NodeOptions & node_opti
9998
clock_ = get_clock();
10099

101100
logger_configure_ = std::make_unique<autoware_utils::LoggerLevelConfigure>(this);
102-
published_time_publisher_ =
103-
std::make_unique<autoware_utils::PublishedTimePublisher>(this);
101+
published_time_publisher_ = std::make_unique<autoware_utils::PublishedTimePublisher>(this);
104102
}
105103

106104
void VelocitySmootherNode::setupSmoother(const double wheelbase)
@@ -1075,8 +1073,7 @@ double VelocitySmootherNode::calcTravelDistance() const
10751073
const auto closest_point = calcProjectedTrajectoryPointFromEgo(prev_output_);
10761074

10771075
if (prev_closest_point_) {
1078-
const double travel_dist =
1079-
autoware_utils::calc_distance2d(*prev_closest_point_, closest_point);
1076+
const double travel_dist = autoware_utils::calc_distance2d(*prev_closest_point_, closest_point);
10801077
return travel_dist;
10811078
}
10821079

‎planning/autoware_velocity_smoother/src/resample.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -17,8 +17,8 @@
1717
#include "autoware/motion_utils/resample/resample.hpp"
1818
#include "autoware/motion_utils/trajectory/conversion.hpp"
1919
#include "autoware/motion_utils/trajectory/trajectory.hpp"
20-
#include "autoware_utils/geometry/geometry.hpp"
2120
#include "autoware/velocity_smoother/trajectory_utils.hpp"
21+
#include "autoware_utils/geometry/geometry.hpp"
2222

2323
#include <algorithm>
2424
#include <vector>

‎planning/autoware_velocity_smoother/src/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.cpp

+4-6
Original file line numberDiff line numberDiff line change
@@ -16,9 +16,10 @@
1616

1717
#include "autoware/motion_utils/resample/resample.hpp"
1818
#include "autoware/motion_utils/trajectory/conversion.hpp"
19-
#include <autoware_utils/geometry/geometry.hpp>
2019
#include "autoware/velocity_smoother/trajectory_utils.hpp"
2120

21+
#include <autoware_utils/geometry/geometry.hpp>
22+
2223
#include <algorithm>
2324
#include <memory>
2425
#include <string>
@@ -358,9 +359,7 @@ TrajectoryPoints AnalyticalJerkConstrainedSmoother::applyLateralAccelerationFilt
358359
continue;
359360
}
360361

361-
if (
362-
autoware_utils::calc_distance2d(output.at(end_index), output.at(index)) <
363-
dist_threshold) {
362+
if (autoware_utils::calc_distance2d(output.at(end_index), output.at(index)) < dist_threshold) {
364363
end_index = index;
365364
min_latacc_velocity = std::min(
366365
static_cast<double>(output.at(index).longitudinal_velocity_mps), min_latacc_velocity);
@@ -491,8 +490,7 @@ bool AnalyticalJerkConstrainedSmoother::applyBackwardDecelFilter(
491490
}
492491
}
493492
for (size_t i = decel_target_index; i > start_index; --i) {
494-
dist += autoware_utils::calc_distance2d(
495-
output_trajectory.at(i - 1), output_trajectory.at(i));
493+
dist += autoware_utils::calc_distance2d(output_trajectory.at(i - 1), output_trajectory.at(i));
496494
dist_to_target.at(i - 1) = dist;
497495
}
498496

‎planning/autoware_velocity_smoother/src/smoother/analytical_jerk_constrained_smoother/velocity_planning_utils.cpp

+3-2
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,7 @@
1515
#include "autoware/velocity_smoother/smoother/analytical_jerk_constrained_smoother/velocity_planning_utils.hpp"
1616

1717
#include "autoware/interpolation/linear_interpolation.hpp"
18+
1819
#include <autoware_utils/geometry/geometry.hpp>
1920

2021
#include <algorithm>
@@ -226,8 +227,8 @@ bool calcStopVelocityWithConstantJerkAccLimit(
226227
std::vector<double> distances;
227228
distances.push_back(distance);
228229
for (size_t i = start_index; i < output_trajectory.size() - 1; ++i) {
229-
distance += autoware_utils::calc_distance2d(
230-
output_trajectory.at(i), output_trajectory.at(i + 1));
230+
distance +=
231+
autoware_utils::calc_distance2d(output_trajectory.at(i), output_trajectory.at(i + 1));
231232
if (distance > xs.back()) {
232233
break;
233234
}

‎planning/autoware_velocity_smoother/src/smoother/jerk_filtered_smoother.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -449,8 +449,8 @@ TrajectoryPoints JerkFilteredSmoother::mergeFilteredTrajectory(
449449
merged.at(i).longitudinal_velocity_mps = current_vel;
450450
merged.at(i).acceleration_mps2 = current_acc;
451451

452-
const double ds = autoware_utils::calc_distance2d(
453-
forward_filtered.at(i + 1), forward_filtered.at(i));
452+
const double ds =
453+
autoware_utils::calc_distance2d(forward_filtered.at(i + 1), forward_filtered.at(i));
454454
const double max_dt =
455455
std::pow(6.0 * ds / std::fabs(j_min), 1.0 / 3.0); // assuming v0 = a0 = 0.
456456
const double dt = std::min(ds / std::max(current_vel, 1.0e-6), max_dt);

‎planning/autoware_velocity_smoother/src/smoother/smoother_base.cpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -17,11 +17,12 @@
1717
#include "autoware/motion_utils/resample/resample.hpp"
1818
#include "autoware/motion_utils/trajectory/conversion.hpp"
1919
#include "autoware/motion_utils/trajectory/trajectory.hpp"
20-
#include <autoware_utils/geometry/geometry.hpp>
21-
#include <autoware_utils/math/unit_conversion.hpp>
2220
#include "autoware/velocity_smoother/resample.hpp"
2321
#include "autoware/velocity_smoother/trajectory_utils.hpp"
2422

23+
#include <autoware_utils/geometry/geometry.hpp>
24+
#include <autoware_utils/math/unit_conversion.hpp>
25+
2526
#include <algorithm>
2627
#include <cmath>
2728
#include <limits>
@@ -274,8 +275,7 @@ TrajectoryPoints SmootherBase::applySteeringRateLimit(
274275
const auto mean_vel =
275276
(output.at(i).longitudinal_velocity_mps + output.at(i + 1).longitudinal_velocity_mps) / 2.0;
276277
const auto target_mean_vel =
277-
mean_vel *
278-
(autoware_utils::deg2rad(base_param_.max_steering_angle_rate) / steer_rate);
278+
mean_vel * (autoware_utils::deg2rad(base_param_.max_steering_angle_rate) / steer_rate);
279279

280280
for (size_t k = 0; k < 2; k++) {
281281
auto & velocity = output.at(i + k).longitudinal_velocity_mps;

‎planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -51,12 +51,12 @@ namespace autoware::behavior_velocity_planner
5151
{
5252
namespace bg = boost::geometry;
5353
using autoware::universe_utils::Polygon2d;
54-
using autoware_utils::StopWatch;
5554
using autoware_internal_planning_msgs::msg::PathWithLaneId;
5655
using autoware_perception_msgs::msg::ObjectClassification;
5756
using autoware_perception_msgs::msg::PredictedObject;
5857
using autoware_perception_msgs::msg::PredictedObjects;
5958
using autoware_perception_msgs::msg::TrafficLightElement;
59+
using autoware_utils::StopWatch;
6060
using lanelet::autoware::Crosswalk;
6161

6262
namespace

‎planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/utils.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -16,9 +16,9 @@
1616
#define UTILS_HPP_
1717

1818
#include <autoware/behavior_velocity_planner_common/utilization/arc_lane_util.hpp>
19-
#include <autoware_lanelet2_extension/regulatory_elements/virtual_traffic_light.hpp>
2019
#include <autoware/universe_utils/geometry/boost_geometry.hpp>
2120
#include <autoware/universe_utils/geometry/geometry.hpp>
21+
#include <autoware_lanelet2_extension/regulatory_elements/virtual_traffic_light.hpp>
2222

2323
#include <autoware_internal_planning_msgs/msg/path_with_lane_id.hpp>
2424
#include <tier4_v2x_msgs/msg/key_value.hpp>

0 commit comments

Comments
 (0)
Please sign in to comment.