Skip to content

Commit

Permalink
style(pre-commit): autofix
Browse files Browse the repository at this point in the history
  • Loading branch information
pre-commit-ci[bot] committed Feb 19, 2025
1 parent 735ef8e commit 3ccba1c
Show file tree
Hide file tree
Showing 54 changed files with 183 additions and 199 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -61,10 +61,10 @@ namespace autoware::velocity_smoother
using autoware_planning_msgs::msg::Trajectory;
using autoware_planning_msgs::msg::TrajectoryPoint;
using TrajectoryPoints = std::vector<TrajectoryPoint>;
using autoware_utils::DiagnosticsInterface;
using autoware_adapi_v1_msgs::msg::OperationModeState;
using autoware_internal_debug_msgs::msg::Float32Stamped;
using autoware_internal_debug_msgs::msg::Float64Stamped;
using autoware_utils::DiagnosticsInterface;
using geometry_msgs::msg::AccelWithCovarianceStamped;
using geometry_msgs::msg::Pose;
using geometry_msgs::msg::PoseStamped;
Expand Down Expand Up @@ -270,8 +270,7 @@ class VelocitySmootherNode : public rclcpp::Node
rclcpp::Publisher<Float32Stamped>::SharedPtr debug_closest_jerk_;
rclcpp::Publisher<Float64Stamped>::SharedPtr debug_calculation_time_;
rclcpp::Publisher<Float32Stamped>::SharedPtr debug_closest_max_velocity_;
rclcpp::Publisher<autoware_utils::ProcessingTimeDetail>::SharedPtr
debug_processing_time_detail_;
rclcpp::Publisher<autoware_utils::ProcessingTimeDetail>::SharedPtr debug_processing_time_detail_;

// For Jerk Filtered Algorithm Debug
rclcpp::Publisher<Trajectory>::SharedPtr pub_forward_filtered_trajectory_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,9 +16,9 @@
#define AUTOWARE__VELOCITY_SMOOTHER__SMOOTHER__ANALYTICAL_JERK_CONSTRAINED_SMOOTHER__ANALYTICAL_JERK_CONSTRAINED_SMOOTHER_HPP_ // NOLINT

#include "autoware/motion_utils/trajectory/trajectory.hpp"
#include "autoware_utils/system/time_keeper.hpp"
#include "autoware/velocity_smoother/smoother/analytical_jerk_constrained_smoother/velocity_planning_utils.hpp"
#include "autoware/velocity_smoother/smoother/smoother_base.hpp"
#include "autoware_utils/system/time_keeper.hpp"
#include "rclcpp/rclcpp.hpp"
#include "tf2/utils.h"

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,9 +17,9 @@

#include "autoware/motion_utils/trajectory/trajectory.hpp"
#include "autoware/qp_interface/qp_interface.hpp"
#include "autoware/velocity_smoother/smoother/smoother_base.hpp"
#include "autoware_utils/geometry/geometry.hpp"
#include "autoware_utils/system/time_keeper.hpp"
#include "autoware/velocity_smoother/smoother/smoother_base.hpp"

#include "autoware_planning_msgs/msg/trajectory_point.hpp"

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,9 +17,9 @@

#include "autoware/motion_utils/trajectory/trajectory.hpp"
#include "autoware/osqp_interface/osqp_interface.hpp"
#include "autoware/velocity_smoother/smoother/smoother_base.hpp"
#include "autoware_utils/geometry/geometry.hpp"
#include "autoware_utils/system/time_keeper.hpp"
#include "autoware/velocity_smoother/smoother/smoother_base.hpp"

#include "autoware_planning_msgs/msg/trajectory_point.hpp"

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,9 +17,9 @@

#include "autoware/motion_utils/trajectory/trajectory.hpp"
#include "autoware/osqp_interface/osqp_interface.hpp"
#include "autoware/velocity_smoother/smoother/smoother_base.hpp"
#include "autoware_utils/geometry/geometry.hpp"
#include "autoware_utils/system/time_keeper.hpp"
#include "autoware/velocity_smoother/smoother/smoother_base.hpp"

#include "autoware_planning_msgs/msg/trajectory_point.hpp"

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,8 @@
#ifndef AUTOWARE__VELOCITY_SMOOTHER__SMOOTHER__SMOOTHER_BASE_HPP_
#define AUTOWARE__VELOCITY_SMOOTHER__SMOOTHER__SMOOTHER_BASE_HPP_

#include "autoware_utils/system/time_keeper.hpp"
#include "autoware/velocity_smoother/resample.hpp"
#include "autoware_utils/system/time_keeper.hpp"
#include "rclcpp/rclcpp.hpp"

#include "autoware_planning_msgs/msg/trajectory_point.hpp"
Expand Down
15 changes: 6 additions & 9 deletions planning/autoware_velocity_smoother/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,10 +15,10 @@
#include "autoware/velocity_smoother/node.hpp"

#include "autoware/motion_utils/marker/marker_helper.hpp"
#include "autoware_utils/ros/update_param.hpp"
#include "autoware/velocity_smoother/smoother/jerk_filtered_smoother.hpp"
#include "autoware/velocity_smoother/smoother/l2_pseudo_jerk_smoother.hpp"
#include "autoware/velocity_smoother/smoother/linf_pseudo_jerk_smoother.hpp"
#include "autoware_utils/ros/update_param.hpp"

#include <autoware_vehicle_info_utils/vehicle_info_utils.hpp>

Expand Down Expand Up @@ -50,10 +50,9 @@ VelocitySmootherNode::VelocitySmootherNode(const rclcpp::NodeOptions & node_opti

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

// create smoother
setupSmoother(wheelbase_);
Expand Down Expand Up @@ -99,8 +98,7 @@ VelocitySmootherNode::VelocitySmootherNode(const rclcpp::NodeOptions & node_opti
clock_ = get_clock();

logger_configure_ = std::make_unique<autoware_utils::LoggerLevelConfigure>(this);
published_time_publisher_ =
std::make_unique<autoware_utils::PublishedTimePublisher>(this);
published_time_publisher_ = std::make_unique<autoware_utils::PublishedTimePublisher>(this);
}

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

if (prev_closest_point_) {
const double travel_dist =
autoware_utils::calc_distance2d(*prev_closest_point_, closest_point);
const double travel_dist = autoware_utils::calc_distance2d(*prev_closest_point_, closest_point);
return travel_dist;
}

Expand Down
2 changes: 1 addition & 1 deletion planning/autoware_velocity_smoother/src/resample.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,8 +17,8 @@
#include "autoware/motion_utils/resample/resample.hpp"
#include "autoware/motion_utils/trajectory/conversion.hpp"
#include "autoware/motion_utils/trajectory/trajectory.hpp"
#include "autoware_utils/geometry/geometry.hpp"
#include "autoware/velocity_smoother/trajectory_utils.hpp"
#include "autoware_utils/geometry/geometry.hpp"

#include <algorithm>
#include <vector>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,9 +16,10 @@

#include "autoware/motion_utils/resample/resample.hpp"
#include "autoware/motion_utils/trajectory/conversion.hpp"
#include <autoware_utils/geometry/geometry.hpp>
#include "autoware/velocity_smoother/trajectory_utils.hpp"

#include <autoware_utils/geometry/geometry.hpp>

#include <algorithm>
#include <memory>
#include <string>
Expand Down Expand Up @@ -358,9 +359,7 @@ TrajectoryPoints AnalyticalJerkConstrainedSmoother::applyLateralAccelerationFilt
continue;
}

if (
autoware_utils::calc_distance2d(output.at(end_index), output.at(index)) <
dist_threshold) {
if (autoware_utils::calc_distance2d(output.at(end_index), output.at(index)) < dist_threshold) {
end_index = index;
min_latacc_velocity = std::min(
static_cast<double>(output.at(index).longitudinal_velocity_mps), min_latacc_velocity);
Expand Down Expand Up @@ -491,8 +490,7 @@ bool AnalyticalJerkConstrainedSmoother::applyBackwardDecelFilter(
}
}
for (size_t i = decel_target_index; i > start_index; --i) {
dist += autoware_utils::calc_distance2d(
output_trajectory.at(i - 1), output_trajectory.at(i));
dist += autoware_utils::calc_distance2d(output_trajectory.at(i - 1), output_trajectory.at(i));
dist_to_target.at(i - 1) = dist;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
#include "autoware/velocity_smoother/smoother/analytical_jerk_constrained_smoother/velocity_planning_utils.hpp"

#include "autoware/interpolation/linear_interpolation.hpp"

#include <autoware_utils/geometry/geometry.hpp>

#include <algorithm>
Expand Down Expand Up @@ -226,8 +227,8 @@ bool calcStopVelocityWithConstantJerkAccLimit(
std::vector<double> distances;
distances.push_back(distance);
for (size_t i = start_index; i < output_trajectory.size() - 1; ++i) {
distance += autoware_utils::calc_distance2d(
output_trajectory.at(i), output_trajectory.at(i + 1));
distance +=
autoware_utils::calc_distance2d(output_trajectory.at(i), output_trajectory.at(i + 1));
if (distance > xs.back()) {
break;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -449,8 +449,8 @@ TrajectoryPoints JerkFilteredSmoother::mergeFilteredTrajectory(
merged.at(i).longitudinal_velocity_mps = current_vel;
merged.at(i).acceleration_mps2 = current_acc;

const double ds = autoware_utils::calc_distance2d(
forward_filtered.at(i + 1), forward_filtered.at(i));
const double ds =
autoware_utils::calc_distance2d(forward_filtered.at(i + 1), forward_filtered.at(i));
const double max_dt =
std::pow(6.0 * ds / std::fabs(j_min), 1.0 / 3.0); // assuming v0 = a0 = 0.
const double dt = std::min(ds / std::max(current_vel, 1.0e-6), max_dt);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,11 +17,12 @@
#include "autoware/motion_utils/resample/resample.hpp"
#include "autoware/motion_utils/trajectory/conversion.hpp"
#include "autoware/motion_utils/trajectory/trajectory.hpp"
#include <autoware_utils/geometry/geometry.hpp>
#include <autoware_utils/math/unit_conversion.hpp>
#include "autoware/velocity_smoother/resample.hpp"
#include "autoware/velocity_smoother/trajectory_utils.hpp"

#include <autoware_utils/geometry/geometry.hpp>
#include <autoware_utils/math/unit_conversion.hpp>

#include <algorithm>
#include <cmath>
#include <limits>
Expand Down Expand Up @@ -274,8 +275,7 @@ TrajectoryPoints SmootherBase::applySteeringRateLimit(
const auto mean_vel =
(output.at(i).longitudinal_velocity_mps + output.at(i + 1).longitudinal_velocity_mps) / 2.0;
const auto target_mean_vel =
mean_vel *
(autoware_utils::deg2rad(base_param_.max_steering_angle_rate) / steer_rate);
mean_vel * (autoware_utils::deg2rad(base_param_.max_steering_angle_rate) / steer_rate);

for (size_t k = 0; k < 2; k++) {
auto & velocity = output.at(i + k).longitudinal_velocity_mps;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,8 @@ PlannerParam PlannerParam::init(rclcpp::Node & node, const std::string & ns)
get_or_declare_parameter<double>(node, ns + ".backward_detection_length");
param.ignore_width_from_center_line =
get_or_declare_parameter<double>(node, ns + ".ignore_width_from_center_line");
param.adjacent_extend_width = get_or_declare_parameter<double>(node, ns + ".adjacent_extend_width");
param.adjacent_extend_width =
get_or_declare_parameter<double>(node, ns + ".adjacent_extend_width");
param.opposite_adjacent_extend_width =
get_or_declare_parameter<double>(node, ns + ".opposite_adjacent_extend_width");
param.max_future_movement_time =
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -100,8 +100,8 @@ std::optional<size_t> getFirstPointIntersectsLineByFootprint(
const auto line2d = line.basicLineString();
for (auto i = start; i <= lane_end; ++i) {
const auto & base_pose = path_ip.points.at(i).point.pose;
const auto path_footprint = autoware_utils::transform_vector(
footprint, autoware_utils::pose2transform(base_pose));
const auto path_footprint =
autoware_utils::transform_vector(footprint, autoware_utils::pose2transform(base_pose));
if (boost::geometry::intersects(path_footprint, line2d)) {
return std::make_optional<size_t>(i);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -106,8 +106,8 @@ visualization_msgs::msg::MarkerArray createCrosswalkMarkers(
for (size_t i = 0; i < debug_data.ego_polygons.size(); ++i) {
const auto & points = debug_data.ego_polygons.at(i);
auto marker = create_default_marker(
"map", now, "vehicle polygon", uid + i, Marker::LINE_STRIP, create_marker_scale(0.1, 0.0, 0.0),
create_marker_color(1.0, 1.0, 0.0, 0.999));
"map", now, "vehicle polygon", uid + i, Marker::LINE_STRIP,
create_marker_scale(0.1, 0.0, 0.0), create_marker_color(1.0, 1.0, 0.0, 0.999));
marker.points = points;
// marker.points.push_back(marker.points.front());
msg.markers.push_back(marker);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,8 @@ CrosswalkModuleManager::CrosswalkModuleManager(rclcpp::Node & node)

// for crosswalk parameters
auto & cp = crosswalk_planner_param_;
cp.show_processing_time = get_or_declare_parameter<bool>(node, ns + ".common.show_processing_time");
cp.show_processing_time =
get_or_declare_parameter<bool>(node, ns + ".common.show_processing_time");

// param for input data
cp.traffic_light_state_timeout =
Expand All @@ -47,8 +48,8 @@ CrosswalkModuleManager::CrosswalkModuleManager(rclcpp::Node & node)
// param for stop position
cp.stop_distance_from_crosswalk =
get_or_declare_parameter<double>(node, ns + ".stop_position.stop_distance_from_crosswalk");
cp.stop_distance_from_object_preferred =
get_or_declare_parameter<double>(node, ns + ".stop_position.stop_distance_from_object_preferred");
cp.stop_distance_from_object_preferred = get_or_declare_parameter<double>(
node, ns + ".stop_position.stop_distance_from_object_preferred");
cp.stop_distance_from_object_limit =
get_or_declare_parameter<double>(node, ns + ".stop_position.stop_distance_from_object_limit");
cp.stop_position_threshold =
Expand All @@ -67,10 +68,12 @@ CrosswalkModuleManager::CrosswalkModuleManager(rclcpp::Node & node)
// param for ego velocity
cp.min_slow_down_velocity =
get_or_declare_parameter<double>(node, ns + ".slow_down.min_slow_down_velocity");
cp.max_slow_down_jerk = get_or_declare_parameter<double>(node, ns + ".slow_down.max_slow_down_jerk");
cp.max_slow_down_jerk =
get_or_declare_parameter<double>(node, ns + ".slow_down.max_slow_down_jerk");
cp.max_slow_down_accel =
get_or_declare_parameter<double>(node, ns + ".slow_down.max_slow_down_accel");
cp.no_relax_velocity = get_or_declare_parameter<double>(node, ns + ".slow_down.no_relax_velocity");
cp.no_relax_velocity =
get_or_declare_parameter<double>(node, ns + ".slow_down.no_relax_velocity");

// param for stuck vehicle
cp.enable_stuck_check_in_intersection =
Expand All @@ -81,7 +84,8 @@ CrosswalkModuleManager::CrosswalkModuleManager(rclcpp::Node & node)
get_or_declare_parameter<double>(node, ns + ".stuck_vehicle.max_stuck_vehicle_lateral_offset");
cp.required_clearance =
get_or_declare_parameter<double>(node, ns + ".stuck_vehicle.required_clearance");
cp.min_acc_for_stuck_vehicle = get_or_declare_parameter<double>(node, ns + ".stuck_vehicle.min_acc");
cp.min_acc_for_stuck_vehicle =
get_or_declare_parameter<double>(node, ns + ".stuck_vehicle.min_acc");
cp.max_jerk_for_stuck_vehicle =
get_or_declare_parameter<double>(node, ns + ".stuck_vehicle.max_jerk");
cp.min_jerk_for_stuck_vehicle =
Expand Down Expand Up @@ -143,7 +147,8 @@ CrosswalkModuleManager::CrosswalkModuleManager(rclcpp::Node & node)
get_or_declare_parameter<float>(node, ns + ".occlusion.slow_down_velocity");
cp.occlusion_time_buffer = get_or_declare_parameter<double>(node, ns + ".occlusion.time_buffer");
cp.occlusion_min_size = get_or_declare_parameter<double>(node, ns + ".occlusion.min_size");
cp.occlusion_free_space_max = get_or_declare_parameter<int>(node, ns + ".occlusion.free_space_max");
cp.occlusion_free_space_max =
get_or_declare_parameter<int>(node, ns + ".occlusion.free_space_max");
cp.occlusion_occupied_min = get_or_declare_parameter<int>(node, ns + ".occlusion.occupied_min");
cp.occlusion_ignore_with_traffic_light =
get_or_declare_parameter<bool>(node, ns + ".occlusion.ignore_with_traffic_light");
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -98,8 +98,7 @@ Polygon2d createMultiStepPolygon(
{
Polygon2d multi_step_polygon{};
for (size_t i = start_idx; i <= end_idx; ++i) {
offsetPolygon2d(
autoware_utils::get_pose(obj_path_points.at(i)), polygon, multi_step_polygon);
offsetPolygon2d(autoware_utils::get_pose(obj_path_points.at(i)), polygon, multi_step_polygon);
}

Polygon2d hull_multi_step_polygon{};
Expand Down Expand Up @@ -662,8 +661,7 @@ std::optional<double> CrosswalkModule::findEgoPassageDirectionAlongPath(
for (unsigned i = 0; i < path.points.size() - 1; ++i) {
const auto & start = path.points.at(i).point.pose.position;
const auto & end = path.points.at(i + 1).point.pose.position;
if (const auto intersect =
autoware_utils::intersect(line_start, line_end, start, end);
if (const auto intersect = autoware_utils::intersect(line_start, line_end, start, end);
intersect.has_value()) {
return intersect;
}
Expand Down Expand Up @@ -694,8 +692,7 @@ std::optional<double> CrosswalkModule::findObjectPassageDirectionAlongVehicleLan
for (unsigned i = 0; i < path.path.size() - 1; ++i) {
const auto & start = path.path.at(i).position;
const auto & end = path.path.at(i + 1).position;
if (const auto intersect =
autoware_utils::intersect(line_start, line_end, start, end);
if (const auto intersect = autoware_utils::intersect(line_start, line_end, start, end);
intersect.has_value()) {
return std::make_optional(std::make_pair(i, intersect.value()));
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,9 +18,9 @@
#include "autoware/behavior_velocity_crosswalk_module/util.hpp"

#include <autoware/behavior_velocity_rtc_interface/scene_module_interface_with_rtc.hpp>
#include <autoware_lanelet2_extension/regulatory_elements/crosswalk.hpp>
#include <autoware_utils/geometry/boost_geometry.hpp>
#include <autoware_utils/system/stop_watch.hpp>
#include <autoware_lanelet2_extension/regulatory_elements/crosswalk.hpp>
#include <rclcpp/rclcpp.hpp>

#include <autoware_internal_debug_msgs/msg/string_stamped.hpp>
Expand Down Expand Up @@ -50,13 +50,13 @@
namespace autoware::behavior_velocity_planner
{
namespace bg = boost::geometry;
using autoware_utils::Polygon2d;
using autoware_utils::StopWatch;
using autoware_internal_planning_msgs::msg::PathWithLaneId;
using autoware_perception_msgs::msg::ObjectClassification;
using autoware_perception_msgs::msg::PredictedObject;
using autoware_perception_msgs::msg::PredictedObjects;
using autoware_perception_msgs::msg::TrafficLightElement;
using autoware_utils::Polygon2d;
using autoware_utils::StopWatch;
using lanelet::autoware::Crosswalk;

namespace
Expand Down Expand Up @@ -295,8 +295,7 @@ class CrosswalkModule : public SceneModuleInterfaceWithRTC

const bool is_object_away_from_path =
!attention_area.outer().empty() &&
boost::geometry::distance(
autoware_utils::from_msg(position).to_2d(), attention_area) > 0.5;
boost::geometry::distance(autoware_utils::from_msg(position).to_2d(), attention_area) > 0.5;

// add new object
if (objects.count(uuid) == 0) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,9 +17,9 @@
#include <autoware/behavior_velocity_planner_common/utilization/util.hpp>
#include <autoware/motion_utils/trajectory/path_with_lane_id.hpp>
#include <autoware/motion_utils/trajectory/trajectory.hpp>
#include <autoware_lanelet2_extension/utility/query.hpp>
#include <autoware_utils/geometry/boost_geometry.hpp>
#include <autoware_utils/geometry/geometry.hpp>
#include <autoware_lanelet2_extension/utility/query.hpp>

#include <autoware_perception_msgs/msg/predicted_objects.hpp>

Expand Down
Loading

0 comments on commit 3ccba1c

Please sign in to comment.