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] authored and mitsudome-r committed Jan 27, 2025
1 parent 9ad78e6 commit 4fd938a
Show file tree
Hide file tree
Showing 140 changed files with 470 additions and 374 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -15,9 +15,9 @@
#ifndef AUTOWARE__MOTION_UTILS__RESAMPLE__RESAMPLE_HPP_
#define AUTOWARE__MOTION_UTILS__RESAMPLE__RESAMPLE_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 "autoware_internal_planning_msgs/msg/path_with_lane_id.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,11 +15,11 @@
#ifndef AUTOWARE__MOTION_UTILS__TRAJECTORY__CONVERSION_HPP_
#define AUTOWARE__MOTION_UTILS__TRAJECTORY__CONVERSION_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"
#include "autoware_internal_planning_msgs/msg/detail/path_with_lane_id__struct.hpp"

#include <vector>

Expand Down Expand Up @@ -95,7 +95,8 @@ inline TrajectoryPoints convertToTrajectoryPoints(
}

template <class T>
autoware_internal_planning_msgs::msg::PathWithLaneId convertToPathWithLaneId([[maybe_unused]] const T & input)
autoware_internal_planning_msgs::msg::PathWithLaneId convertToPathWithLaneId(
[[maybe_unused]] const T & input)
{
static_assert(sizeof(T) == 0, "Only specializations of convertToPathWithLaneId can be used.");
throw std::logic_error("Only specializations of convertToPathWithLaneId can be used.");
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,8 +17,8 @@

#include "autoware/universe_utils/geometry/geometry.hpp"

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

#include <boost/optional.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,9 +23,9 @@
#include <Eigen/Geometry>
#include <rclcpp/logging.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 <autoware_internal_planning_msgs/msg/path_point_with_lane_id.hpp>

#include <algorithm>
#include <limits>
Expand Down Expand Up @@ -58,7 +58,8 @@ void validateNonEmpty(const T & points)

extern template void validateNonEmpty<std::vector<autoware_planning_msgs::msg::PathPoint>>(
const std::vector<autoware_planning_msgs::msg::PathPoint> &);
extern template void validateNonEmpty<std::vector<autoware_internal_planning_msgs::msg::PathPointWithLaneId>>(
extern template void
validateNonEmpty<std::vector<autoware_internal_planning_msgs::msg::PathPointWithLaneId>>(
const std::vector<autoware_internal_planning_msgs::msg::PathPointWithLaneId> &);
extern template void validateNonEmpty<std::vector<autoware_planning_msgs::msg::TrajectoryPoint>>(
const std::vector<autoware_planning_msgs::msg::TrajectoryPoint> &);
Expand Down Expand Up @@ -311,7 +312,8 @@ size_t findNearestIndex(const T & points, const geometry_msgs::msg::Point & poin
extern template size_t findNearestIndex<std::vector<autoware_planning_msgs::msg::PathPoint>>(
const std::vector<autoware_planning_msgs::msg::PathPoint> & points,
const geometry_msgs::msg::Point & point);
extern template size_t findNearestIndex<std::vector<autoware_internal_planning_msgs::msg::PathPointWithLaneId>>(
extern template size_t
findNearestIndex<std::vector<autoware_internal_planning_msgs::msg::PathPointWithLaneId>>(
const std::vector<autoware_internal_planning_msgs::msg::PathPointWithLaneId> & points,
const geometry_msgs::msg::Point & point);
extern template size_t findNearestIndex<std::vector<autoware_planning_msgs::msg::TrajectoryPoint>>(
Expand Down Expand Up @@ -461,10 +463,11 @@ 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>>(
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);
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);
extern template double
calcLongitudinalOffsetToSegment<std::vector<autoware_planning_msgs::msg::TrajectoryPoint>>(
const std::vector<autoware_planning_msgs::msg::TrajectoryPoint> & points, const size_t seg_idx,
Expand Down Expand Up @@ -734,8 +737,8 @@ extern template double calcSignedArcLength<std::vector<autoware_planning_msgs::m
const size_t dst_idx);
extern template double
calcSignedArcLength<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);
const std::vector<autoware_internal_planning_msgs::msg::PathPointWithLaneId> & points,
const size_t src_idx, const size_t dst_idx);
extern template double
calcSignedArcLength<std::vector<autoware_planning_msgs::msg::TrajectoryPoint>>(
const std::vector<autoware_planning_msgs::msg::TrajectoryPoint> & points, const size_t src_idx,
Expand Down Expand Up @@ -782,10 +785,10 @@ 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>>(
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> 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>
calcSignedArcLengthPartialSum<std::vector<autoware_planning_msgs::msg::TrajectoryPoint>>(
const std::vector<autoware_planning_msgs::msg::TrajectoryPoint> & points, const size_t src_idx,
Expand Down Expand Up @@ -862,8 +865,8 @@ extern template double calcSignedArcLength<std::vector<autoware_planning_msgs::m
const geometry_msgs::msg::Point & dst_point);
extern template double
calcSignedArcLength<std::vector<autoware_internal_planning_msgs::msg::PathPointWithLaneId>>(
const std::vector<autoware_internal_planning_msgs::msg::PathPointWithLaneId> & points, const size_t src_idx,
const geometry_msgs::msg::Point & dst_point);
const std::vector<autoware_internal_planning_msgs::msg::PathPointWithLaneId> & points,
const size_t src_idx, const geometry_msgs::msg::Point & dst_point);
extern template double
calcSignedArcLength<std::vector<autoware_planning_msgs::msg::TrajectoryPoint>>(
const std::vector<autoware_planning_msgs::msg::TrajectoryPoint> & points, const size_t src_idx,
Expand Down Expand Up @@ -936,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 @@ -1032,7 +1036,8 @@ extern template std::vector<std::pair<double, std::pair<double, double>>>
calcCurvatureAndSegmentLength<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>>>
calcCurvatureAndSegmentLength<std::vector<autoware_internal_planning_msgs::msg::PathPointWithLaneId>>(
calcCurvatureAndSegmentLength<
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>>>
calcCurvatureAndSegmentLength<std::vector<autoware_planning_msgs::msg::TrajectoryPoint>>(
Expand Down Expand Up @@ -1147,8 +1152,8 @@ calcLongitudinalOffsetPoint<std::vector<autoware_planning_msgs::msg::PathPoint>>
const double offset, const bool throw_exception = false);
extern template std::optional<geometry_msgs::msg::Point>
calcLongitudinalOffsetPoint<std::vector<autoware_internal_planning_msgs::msg::PathPointWithLaneId>>(
const std::vector<autoware_internal_planning_msgs::msg::PathPointWithLaneId> & points, const size_t src_idx,
const double offset, const bool throw_exception = false);
const std::vector<autoware_internal_planning_msgs::msg::PathPointWithLaneId> & points,
const size_t src_idx, const double offset, const bool throw_exception = false);
extern template std::optional<geometry_msgs::msg::Point>
calcLongitudinalOffsetPoint<std::vector<autoware_planning_msgs::msg::TrajectoryPoint>>(
const std::vector<autoware_planning_msgs::msg::TrajectoryPoint> & points, const size_t src_idx,
Expand Down Expand Up @@ -1293,9 +1298,9 @@ calcLongitudinalOffsetPose<std::vector<autoware_planning_msgs::msg::PathPoint>>(
const bool throw_exception = false);
extern template std::optional<geometry_msgs::msg::Pose>
calcLongitudinalOffsetPose<std::vector<autoware_internal_planning_msgs::msg::PathPointWithLaneId>>(
const std::vector<autoware_internal_planning_msgs::msg::PathPointWithLaneId> & points, const size_t src_idx,
const double offset, const bool set_orientation_from_position_direction = true,
const bool throw_exception = false);
const std::vector<autoware_internal_planning_msgs::msg::PathPointWithLaneId> & points,
const size_t src_idx, const double offset,
const bool set_orientation_from_position_direction = true, const bool throw_exception = false);
extern template std::optional<geometry_msgs::msg::Pose>
calcLongitudinalOffsetPose<std::vector<autoware_planning_msgs::msg::TrajectoryPoint>>(
const std::vector<autoware_planning_msgs::msg::TrajectoryPoint> & points, const size_t src_idx,
Expand Down Expand Up @@ -1906,7 +1911,8 @@ void insertOrientation(T & points, const bool is_driving_forward)

extern template void insertOrientation<std::vector<autoware_planning_msgs::msg::PathPoint>>(
std::vector<autoware_planning_msgs::msg::PathPoint> & points, const bool is_driving_forward);
extern template void insertOrientation<std::vector<autoware_internal_planning_msgs::msg::PathPointWithLaneId>>(
extern template void
insertOrientation<std::vector<autoware_internal_planning_msgs::msg::PathPointWithLaneId>>(
std::vector<autoware_internal_planning_msgs::msg::PathPointWithLaneId> & points,
const bool is_driving_forward);
extern template void insertOrientation<std::vector<autoware_planning_msgs::msg::TrajectoryPoint>>(
Expand Down Expand Up @@ -2051,8 +2057,8 @@ extern template double calcSignedArcLength<std::vector<autoware_planning_msgs::m
const geometry_msgs::msg::Point & dst_point, const size_t dst_seg_idx);
extern template double
calcSignedArcLength<std::vector<autoware_internal_planning_msgs::msg::PathPointWithLaneId>>(
const std::vector<autoware_internal_planning_msgs::msg::PathPointWithLaneId> & points, const size_t src_idx,
const geometry_msgs::msg::Point & dst_point, const size_t dst_seg_idx);
const std::vector<autoware_internal_planning_msgs::msg::PathPointWithLaneId> & points,
const size_t src_idx, const geometry_msgs::msg::Point & dst_point, const size_t dst_seg_idx);
extern template double
calcSignedArcLength<std::vector<autoware_planning_msgs::msg::TrajectoryPoint>>(
const std::vector<autoware_planning_msgs::msg::TrajectoryPoint> & points, const size_t src_idx,
Expand Down Expand Up @@ -2272,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 Expand Up @@ -2460,7 +2466,8 @@ double calcYawDeviation(
extern template double calcYawDeviation<std::vector<autoware_planning_msgs::msg::PathPoint>>(
const std::vector<autoware_planning_msgs::msg::PathPoint> & points,
const geometry_msgs::msg::Pose & pose, const bool throw_exception = false);
extern template double calcYawDeviation<std::vector<autoware_internal_planning_msgs::msg::PathPointWithLaneId>>(
extern template double
calcYawDeviation<std::vector<autoware_internal_planning_msgs::msg::PathPointWithLaneId>>(
const std::vector<autoware_internal_planning_msgs::msg::PathPointWithLaneId> & points,
const geometry_msgs::msg::Pose & pose, const bool throw_exception = false);
extern template double calcYawDeviation<std::vector<autoware_planning_msgs::msg::TrajectoryPoint>>(
Expand Down Expand Up @@ -2495,7 +2502,8 @@ extern template bool isTargetPointFront<std::vector<autoware_planning_msgs::msg:
const std::vector<autoware_planning_msgs::msg::PathPoint> & points,
const geometry_msgs::msg::Point & base_point, const geometry_msgs::msg::Point & target_point,
const double threshold = 0.0);
extern template bool isTargetPointFront<std::vector<autoware_internal_planning_msgs::msg::PathPointWithLaneId>>(
extern template bool
isTargetPointFront<std::vector<autoware_internal_planning_msgs::msg::PathPointWithLaneId>>(
const std::vector<autoware_internal_planning_msgs::msg::PathPointWithLaneId> & points,
const geometry_msgs::msg::Point & base_point, const geometry_msgs::msg::Point & target_point,
const double threshold = 0.0);
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 @@ -22,8 +22,8 @@
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>autoware_adapi_v1_msgs</depend>
<depend>autoware_interpolation</depend>
<depend>autoware_internal_planning_msgs</depend>
<depend>autoware_interpolation</depend>
<depend>autoware_planning_msgs</depend>
<depend>autoware_universe_utils</depend>
<depend>autoware_vehicle_msgs</depend>
Expand Down
4 changes: 2 additions & 2 deletions common/autoware_motion_utils/src/resample/resample.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -360,8 +360,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
4 changes: 2 additions & 2 deletions common/autoware_motion_utils/src/trajectory/interpolation.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,10 +17,10 @@
#include "autoware/interpolation/linear_interpolation.hpp"
#include "autoware/motion_utils/trajectory/trajectory.hpp"

using autoware_planning_msgs::msg::Trajectory;
using autoware_planning_msgs::msg::TrajectoryPoint;
using autoware_internal_planning_msgs::msg::PathPointWithLaneId;
using autoware_internal_planning_msgs::msg::PathWithLaneId;
using autoware_planning_msgs::msg::Trajectory;
using autoware_planning_msgs::msg::TrajectoryPoint;

namespace autoware::motion_utils
{
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 4fd938a

Please sign in to comment.