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 Jan 17, 2025
1 parent 9f4d606 commit 7201415
Show file tree
Hide file tree
Showing 20 changed files with 126 additions and 109 deletions.
2 changes: 1 addition & 1 deletion common/autoware_interpolation/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -11,8 +11,8 @@
<buildtool_depend>ament_cmake_auto</buildtool_depend>
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>eigen</depend>
<depend>autoware_utils</depend>
<depend>eigen</depend>

<test_depend>ament_cmake_ros</test_depend>
<test_depend>ament_lint_auto</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -89,8 +89,7 @@ geometry_msgs::msg::Pose SplineInterpolationPoints2d::getSplineInterpolatedPose(
{
geometry_msgs::msg::Pose pose;
pose.position = getSplineInterpolatedPoint(idx, s);
pose.orientation =
autoware_utils::create_quaternion_from_yaw(getSplineInterpolatedYaw(idx, s));
pose.orientation = autoware_utils::create_quaternion_from_yaw(getSplineInterpolatedYaw(idx, s));
return pose;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -200,8 +200,8 @@ TEST(spline_interpolation, SplineInterpolationPoints2d)

TEST(spline_interpolation, SplineInterpolationPoints2dPolymorphism)
{
using autoware_utils::create_point;
using autoware_planning_msgs::msg::TrajectoryPoint;
using autoware_utils::create_point;

std::vector<geometry_msgs::msg::Point> points;
points.push_back(create_point(-2.0, -10.0, 0.0));
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,11 +19,11 @@
#include <rclcpp/rclcpp.hpp>

#include <autoware_internal_planning_msgs/msg/control_point.hpp>
#include <autoware_planning_msgs/msg/path_point.hpp>
#include <autoware_internal_planning_msgs/msg/path_point_with_lane_id.hpp>
#include <autoware_internal_planning_msgs/msg/planning_factor.hpp>
#include <autoware_internal_planning_msgs/msg/planning_factor_array.hpp>
#include <autoware_internal_planning_msgs/msg/safety_factor_array.hpp>
#include <autoware_planning_msgs/msg/path_point.hpp>
#include <autoware_planning_msgs/msg/trajectory_point.hpp>
#include <geometry_msgs/msg/pose.hpp>

Expand Down Expand Up @@ -209,10 +209,11 @@ class PlanningFactorInterface
std::vector<PlanningFactor> factors_;
};

extern template void PlanningFactorInterface::add<autoware_internal_planning_msgs::msg::PathPointWithLaneId>(
const std::vector<autoware_internal_planning_msgs::msg::PathPointWithLaneId> &, const Pose &, const Pose &,
const uint16_t behavior, const SafetyFactorArray &, const bool, const double, const double,
const std::string &);
extern template void
PlanningFactorInterface::add<autoware_internal_planning_msgs::msg::PathPointWithLaneId>(
const std::vector<autoware_internal_planning_msgs::msg::PathPointWithLaneId> &, const Pose &,
const Pose &, const uint16_t behavior, const SafetyFactorArray &, const bool, const double,
const double, const std::string &);
extern template void PlanningFactorInterface::add<autoware_planning_msgs::msg::PathPoint>(
const std::vector<autoware_planning_msgs::msg::PathPoint> &, const Pose &, const Pose &,
const uint16_t behavior, const SafetyFactorArray &, const bool, const double, const double,
Expand All @@ -222,10 +223,11 @@ extern template void PlanningFactorInterface::add<autoware_planning_msgs::msg::T
const uint16_t behavior, const SafetyFactorArray &, const bool, const double, const double,
const std::string &);

extern template void PlanningFactorInterface::add<autoware_internal_planning_msgs::msg::PathPointWithLaneId>(
const std::vector<autoware_internal_planning_msgs::msg::PathPointWithLaneId> &, const Pose &, const Pose &,
const Pose &, const uint16_t behavior, const SafetyFactorArray &, const bool, const double,
const double, const std::string &);
extern template void
PlanningFactorInterface::add<autoware_internal_planning_msgs::msg::PathPointWithLaneId>(
const std::vector<autoware_internal_planning_msgs::msg::PathPointWithLaneId> &, const Pose &,
const Pose &, const Pose &, const uint16_t behavior, const SafetyFactorArray &, const bool,
const double, const double, const std::string &);
extern template void PlanningFactorInterface::add<autoware_planning_msgs::msg::PathPoint>(
const std::vector<autoware_planning_msgs::msg::PathPoint> &, const Pose &, const Pose &,
const Pose &, const uint16_t behavior, const SafetyFactorArray &, const bool, const double,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,8 @@
#ifndef AUTOWARE__MOTION_UTILS__RESAMPLE__RESAMPLE_HPP_
#define AUTOWARE__MOTION_UTILS__RESAMPLE__RESAMPLE_HPP_

#include "autoware_planning_msgs/msg/path.hpp"
#include "autoware_internal_planning_msgs/msg/path_with_lane_id.hpp"
#include "autoware_planning_msgs/msg/path.hpp"
#include "autoware_planning_msgs/msg/trajectory.hpp"

#include <vector>
Expand Down Expand Up @@ -137,9 +137,10 @@ autoware_internal_planning_msgs::msg::PathWithLaneId resamplePath(
* @return resampled path
*/
autoware_internal_planning_msgs::msg::PathWithLaneId resamplePath(
const autoware_internal_planning_msgs::msg::PathWithLaneId & input_path, const double resample_interval,
const bool use_akima_spline_for_xy = false, const bool use_lerp_for_z = true,
const bool use_zero_order_hold_for_v = true, const bool resample_input_path_stop_point = true);
const autoware_internal_planning_msgs::msg::PathWithLaneId & input_path,
const double resample_interval, const bool use_akima_spline_for_xy = false,
const bool use_lerp_for_z = true, const bool use_zero_order_hold_for_v = true,
const bool resample_input_path_stop_point = true);

/**
* @brief A resampling function for a path. Note that in a default setting, position xy are
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,8 @@
#ifndef AUTOWARE__MOTION_UTILS__TRAJECTORY__CONVERSION_HPP_
#define AUTOWARE__MOTION_UTILS__TRAJECTORY__CONVERSION_HPP_

#include "autoware_planning_msgs/msg/detail/path__struct.hpp"
#include "autoware_internal_planning_msgs/msg/detail/path_with_lane_id__struct.hpp"
#include "autoware_planning_msgs/msg/detail/path__struct.hpp"
#include "autoware_planning_msgs/msg/detail/trajectory__struct.hpp"
#include "autoware_planning_msgs/msg/detail/trajectory_point__struct.hpp"
#include "std_msgs/msg/header.hpp"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,12 +26,12 @@ std::optional<std::pair<size_t, size_t>> getPathIndexRangeWithLaneId(
const autoware_internal_planning_msgs::msg::PathWithLaneId & path, const int64_t target_lane_id);

size_t findNearestIndexFromLaneId(
const autoware_internal_planning_msgs::msg::PathWithLaneId & path, const geometry_msgs::msg::Point & pos,
const int64_t lane_id);
const autoware_internal_planning_msgs::msg::PathWithLaneId & path,
const geometry_msgs::msg::Point & pos, const int64_t lane_id);

size_t findNearestSegmentIndexFromLaneId(
const autoware_internal_planning_msgs::msg::PathWithLaneId & path, const geometry_msgs::msg::Point & pos,
const int64_t lane_id);
const autoware_internal_planning_msgs::msg::PathWithLaneId & path,
const geometry_msgs::msg::Point & pos, const int64_t lane_id);

// @brief Calculates the path to be followed by the rear wheel center in order to make the vehicle
// center follow the input path
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,8 +23,8 @@
#include <Eigen/Geometry>
#include <rclcpp/logging.hpp>

#include <autoware_planning_msgs/msg/path_point.hpp>
#include <autoware_internal_planning_msgs/msg/path_point_with_lane_id.hpp>
#include <autoware_planning_msgs/msg/path_point.hpp>
#include <autoware_planning_msgs/msg/trajectory_point.hpp>

#include <algorithm>
Expand Down Expand Up @@ -358,8 +358,8 @@ std::optional<size_t> findNearestIndex(
continue;
}

const auto yaw = autoware_utils::calc_yaw_deviation(
autoware_utils::get_pose(points.at(i)), pose);
const auto yaw =
autoware_utils::calc_yaw_deviation(autoware_utils::get_pose(points.at(i)), pose);
if (std::fabs(yaw) > max_yaw) {
continue;
}
Expand Down Expand Up @@ -463,8 +463,8 @@ extern template double
calcLongitudinalOffsetToSegment<std::vector<autoware_planning_msgs::msg::PathPoint>>(
const std::vector<autoware_planning_msgs::msg::PathPoint> & points, const size_t seg_idx,
const geometry_msgs::msg::Point & p_target, const bool throw_exception = false);
extern template double
calcLongitudinalOffsetToSegment<std::vector<autoware_internal_planning_msgs::msg::PathPointWithLaneId>>(
extern template double calcLongitudinalOffsetToSegment<
std::vector<autoware_internal_planning_msgs::msg::PathPointWithLaneId>>(
const std::vector<autoware_internal_planning_msgs::msg::PathPointWithLaneId> & points,
const size_t seg_idx, const geometry_msgs::msg::Point & p_target,
const bool throw_exception = false);
Expand Down Expand Up @@ -785,8 +785,8 @@ extern template std::vector<double>
calcSignedArcLengthPartialSum<std::vector<autoware_planning_msgs::msg::PathPoint>>(
const std::vector<autoware_planning_msgs::msg::PathPoint> & points, const size_t src_idx,
const size_t dst_idx);
extern template std::vector<double>
calcSignedArcLengthPartialSum<std::vector<autoware_internal_planning_msgs::msg::PathPointWithLaneId>>(
extern template std::vector<double> calcSignedArcLengthPartialSum<
std::vector<autoware_internal_planning_msgs::msg::PathPointWithLaneId>>(
const std::vector<autoware_internal_planning_msgs::msg::PathPointWithLaneId> & points,
const size_t src_idx, const size_t dst_idx);
extern template std::vector<double>
Expand Down Expand Up @@ -939,7 +939,8 @@ double calcArcLength(const T & points)

extern template double calcArcLength<std::vector<autoware_planning_msgs::msg::PathPoint>>(
const std::vector<autoware_planning_msgs::msg::PathPoint> & points);
extern template double calcArcLength<std::vector<autoware_internal_planning_msgs::msg::PathPointWithLaneId>>(
extern template double
calcArcLength<std::vector<autoware_internal_planning_msgs::msg::PathPointWithLaneId>>(
const std::vector<autoware_internal_planning_msgs::msg::PathPointWithLaneId> & points);
extern template double calcArcLength<std::vector<autoware_planning_msgs::msg::TrajectoryPoint>>(
const std::vector<autoware_planning_msgs::msg::TrajectoryPoint> & points);
Expand Down Expand Up @@ -1035,7 +1036,8 @@ extern template std::vector<std::pair<double, std::pair<double, double>>>
calc_curvatureAndSegmentLength<std::vector<autoware_planning_msgs::msg::PathPoint>>(
const std::vector<autoware_planning_msgs::msg::PathPoint> & points);
extern template std::vector<std::pair<double, std::pair<double, double>>>
calc_curvatureAndSegmentLength<std::vector<autoware_internal_planning_msgs::msg::PathPointWithLaneId>>(
calc_curvatureAndSegmentLength<
std::vector<autoware_internal_planning_msgs::msg::PathPointWithLaneId>>(
const std::vector<autoware_internal_planning_msgs::msg::PathPointWithLaneId> & points);
extern template std::vector<std::pair<double, std::pair<double, double>>>
calc_curvatureAndSegmentLength<std::vector<autoware_planning_msgs::msg::TrajectoryPoint>>(
Expand Down Expand Up @@ -2090,8 +2092,8 @@ size_t findFirstNearestIndexWithSoftConstraints(
for (size_t i = 0; i < points.size(); ++i) {
const auto squared_dist =
autoware_utils::calc_squared_distance2d(points.at(i), pose.position);
const auto yaw = autoware_utils::calc_yaw_deviation(
autoware_utils::get_pose(points.at(i)), pose);
const auto yaw =
autoware_utils::calc_yaw_deviation(autoware_utils::get_pose(points.at(i)), pose);

if (squared_dist_threshold < squared_dist || yaw_threshold < std::abs(yaw)) {
if (is_within_constraints) {
Expand Down Expand Up @@ -2276,8 +2278,8 @@ calcDistanceToForwardStopPoint<std::vector<autoware_planning_msgs::msg::PathPoin
const std::vector<autoware_planning_msgs::msg::PathPoint> & points_with_twist,
const geometry_msgs::msg::Pose & pose, const double max_dist = std::numeric_limits<double>::max(),
const double max_yaw = std::numeric_limits<double>::max());
extern template std::optional<double>
calcDistanceToForwardStopPoint<std::vector<autoware_internal_planning_msgs::msg::PathPointWithLaneId>>(
extern template std::optional<double> calcDistanceToForwardStopPoint<
std::vector<autoware_internal_planning_msgs::msg::PathPointWithLaneId>>(
const std::vector<autoware_internal_planning_msgs::msg::PathPointWithLaneId> & points_with_twist,
const geometry_msgs::msg::Pose & pose, const double max_dist = std::numeric_limits<double>::max(),
const double max_yaw = std::numeric_limits<double>::max());
Expand Down
2 changes: 1 addition & 1 deletion common/autoware_motion_utils/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -23,9 +23,9 @@
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>autoware_adapi_v1_msgs</depend>
<depend>autoware_internal_planning_msgs</depend>
<depend>autoware_interpolation</depend>
<depend>autoware_planning_msgs</depend>
<depend>autoware_internal_planning_msgs</depend>
<depend>autoware_utils</depend>
<depend>autoware_vehicle_msgs</depend>
<depend>builtin_interfaces</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,10 +19,11 @@

namespace autoware::motion_utils
{
template void PlanningFactorInterface::add<autoware_internal_planning_msgs::msg::PathPointWithLaneId>(
const std::vector<autoware_internal_planning_msgs::msg::PathPointWithLaneId> &, const Pose &, const Pose &,
const uint16_t behavior, const SafetyFactorArray &, const bool, const double, const double,
const std::string &);
template void
PlanningFactorInterface::add<autoware_internal_planning_msgs::msg::PathPointWithLaneId>(
const std::vector<autoware_internal_planning_msgs::msg::PathPointWithLaneId> &, const Pose &,
const Pose &, const uint16_t behavior, const SafetyFactorArray &, const bool, const double,
const double, const std::string &);
template void PlanningFactorInterface::add<autoware_planning_msgs::msg::PathPoint>(
const std::vector<autoware_planning_msgs::msg::PathPoint> &, const Pose &, const Pose &,
const uint16_t behavior, const SafetyFactorArray &, const bool, const double, const double,
Expand All @@ -32,10 +33,11 @@ template void PlanningFactorInterface::add<autoware_planning_msgs::msg::Trajecto
const uint16_t behavior, const SafetyFactorArray &, const bool, const double, const double,
const std::string &);

template void PlanningFactorInterface::add<autoware_internal_planning_msgs::msg::PathPointWithLaneId>(
const std::vector<autoware_internal_planning_msgs::msg::PathPointWithLaneId> &, const Pose &, const Pose &,
const Pose &, const uint16_t behavior, const SafetyFactorArray &, const bool, const double,
const double, const std::string &);
template void
PlanningFactorInterface::add<autoware_internal_planning_msgs::msg::PathPointWithLaneId>(
const std::vector<autoware_internal_planning_msgs::msg::PathPointWithLaneId> &, const Pose &,
const Pose &, const Pose &, const uint16_t behavior, const SafetyFactorArray &, const bool,
const double, const double, const std::string &);
template void PlanningFactorInterface::add<autoware_planning_msgs::msg::PathPoint>(
const std::vector<autoware_planning_msgs::msg::PathPoint> &, const Pose &, const Pose &,
const Pose &, const uint16_t behavior, const SafetyFactorArray &, const bool, const double,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,8 @@
#include <autoware/motion_utils/factor/velocity_factor_interface.hpp>
#include <autoware/motion_utils/trajectory/trajectory.hpp>

#include <autoware_planning_msgs/msg/path_point.hpp>
#include <autoware_internal_planning_msgs/msg/path_point_with_lane_id.hpp>
#include <autoware_planning_msgs/msg/path_point.hpp>
#include <autoware_planning_msgs/msg/trajectory_point.hpp>

#include <string>
Expand Down Expand Up @@ -48,9 +48,10 @@ void VelocityFactorInterface::set(
velocity_factor_.detail = detail;
}

template void VelocityFactorInterface::set<autoware_internal_planning_msgs::msg::PathPointWithLaneId>(
const std::vector<autoware_internal_planning_msgs::msg::PathPointWithLaneId> &, const Pose &, const Pose &,
const VelocityFactorStatus, const std::string &);
template void
VelocityFactorInterface::set<autoware_internal_planning_msgs::msg::PathPointWithLaneId>(
const std::vector<autoware_internal_planning_msgs::msg::PathPointWithLaneId> &, const Pose &,
const Pose &, const VelocityFactorStatus, const std::string &);
template void VelocityFactorInterface::set<autoware_planning_msgs::msg::PathPoint>(
const std::vector<autoware_planning_msgs::msg::PathPoint> &, const Pose &, const Pose &,
const VelocityFactorStatus, const std::string &);
Expand Down
16 changes: 6 additions & 10 deletions common/autoware_motion_utils/src/resample/resample.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -148,8 +148,7 @@ std::vector<geometry_msgs::msg::Pose> resamplePoseVector(
resampled_points.at(i) = pose;
}

const bool is_driving_forward =
autoware_utils::is_driving_forward(points.at(0), points.at(1));
const bool is_driving_forward = autoware_utils::is_driving_forward(points.at(0), points.at(1));
autoware::motion_utils::insertOrientation(resampled_points, is_driving_forward);

// Initial orientation is depend on the initial value of the resampled_arclength
Expand Down Expand Up @@ -264,8 +263,7 @@ autoware_internal_planning_msgs::msg::PathWithLaneId resamplePath(
for (size_t i = 1; i < input_path.points.size(); ++i) {
const auto & prev_pt = input_path.points.at(i - 1).point;
const auto & curr_pt = input_path.points.at(i).point;
const double ds =
autoware_utils::calc_distance2d(prev_pt.pose.position, curr_pt.pose.position);
const double ds = autoware_utils::calc_distance2d(prev_pt.pose.position, curr_pt.pose.position);
input_arclength.push_back(ds + input_arclength.back());
input_pose.push_back(curr_pt.pose);
v_lon.push_back(curr_pt.longitudinal_velocity_mps);
Expand Down Expand Up @@ -360,8 +358,8 @@ autoware_internal_planning_msgs::msg::PathWithLaneId resamplePath(
}

autoware_internal_planning_msgs::msg::PathWithLaneId resamplePath(
const autoware_internal_planning_msgs::msg::PathWithLaneId & input_path, const double resample_interval,
const bool use_akima_spline_for_xy, const bool use_lerp_for_z,
const autoware_internal_planning_msgs::msg::PathWithLaneId & input_path,
const double resample_interval, const bool use_akima_spline_for_xy, const bool use_lerp_for_z,
const bool use_zero_order_hold_for_v, const bool resample_input_path_stop_point)
{
// validate arguments
Expand Down Expand Up @@ -455,8 +453,7 @@ autoware_planning_msgs::msg::Path resamplePath(
for (size_t i = 1; i < input_path.points.size(); ++i) {
const auto & prev_pt = input_path.points.at(i - 1);
const auto & curr_pt = input_path.points.at(i);
const double ds =
autoware_utils::calc_distance2d(prev_pt.pose.position, curr_pt.pose.position);
const double ds = autoware_utils::calc_distance2d(prev_pt.pose.position, curr_pt.pose.position);
input_arclength.push_back(ds + input_arclength.back());
input_pose.push_back(curr_pt.pose);
v_lon.push_back(curr_pt.longitudinal_velocity_mps);
Expand Down Expand Up @@ -612,8 +609,7 @@ autoware_planning_msgs::msg::Trajectory resampleTrajectory(
for (size_t i = 1; i < input_trajectory.points.size(); ++i) {
const auto & prev_pt = input_trajectory.points.at(i - 1);
const auto & curr_pt = input_trajectory.points.at(i);
const double ds =
autoware_utils::calc_distance2d(prev_pt.pose.position, curr_pt.pose.position);
const double ds = autoware_utils::calc_distance2d(prev_pt.pose.position, curr_pt.pose.position);

input_arclength.push_back(ds + input_arclength.back());
input_pose.push_back(curr_pt.pose);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -57,8 +57,7 @@ TrajectoryPoint calcInterpolatedPoint(
TrajectoryPoint interpolated_point{};

// pose interpolation
interpolated_point.pose =
autoware_utils::calc_interpolated_pose(curr_pt, next_pt, clamped_ratio);
interpolated_point.pose = autoware_utils::calc_interpolated_pose(curr_pt, next_pt, clamped_ratio);

// twist interpolation
if (use_zero_order_hold_for_twist) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -56,8 +56,8 @@ std::optional<std::pair<size_t, size_t>> getPathIndexRangeWithLaneId(
}

size_t findNearestIndexFromLaneId(
const autoware_internal_planning_msgs::msg::PathWithLaneId & path, const geometry_msgs::msg::Point & pos,
const int64_t lane_id)
const autoware_internal_planning_msgs::msg::PathWithLaneId & path,
const geometry_msgs::msg::Point & pos, const int64_t lane_id)
{
const auto opt_range = getPathIndexRangeWithLaneId(path, lane_id);
if (opt_range) {
Expand All @@ -77,8 +77,8 @@ size_t findNearestIndexFromLaneId(
}

size_t findNearestSegmentIndexFromLaneId(
const autoware_internal_planning_msgs::msg::PathWithLaneId & path, const geometry_msgs::msg::Point & pos,
const int64_t lane_id)
const autoware_internal_planning_msgs::msg::PathWithLaneId & path,
const geometry_msgs::msg::Point & pos, const int64_t lane_id)
{
const size_t nearest_idx = findNearestIndexFromLaneId(path, pos, lane_id);

Expand Down
Loading

0 comments on commit 7201415

Please sign in to comment.