|
24 | 24 | #include <rclcpp/logging.hpp>
|
25 | 25 |
|
26 | 26 | #include <autoware_planning_msgs/msg/path_point.hpp>
|
27 |
| -#include <autoware_planning_msgs/msg/trajectory_point.hpp> |
28 | 27 | #include <autoware_planning_msgs/msg/path_point_with_lane_id.hpp>
|
| 28 | +#include <autoware_planning_msgs/msg/trajectory_point.hpp> |
29 | 29 |
|
30 | 30 | #include <algorithm>
|
31 | 31 | #include <limits>
|
@@ -58,7 +58,8 @@ void validateNonEmpty(const T & points)
|
58 | 58 |
|
59 | 59 | extern template void validateNonEmpty<std::vector<autoware_planning_msgs::msg::PathPoint>>(
|
60 | 60 | const std::vector<autoware_planning_msgs::msg::PathPoint> &);
|
61 |
| -extern template void validateNonEmpty<std::vector<autoware_planning_msgs::msg::PathPointWithLaneId>>( |
| 61 | +extern template void |
| 62 | +validateNonEmpty<std::vector<autoware_planning_msgs::msg::PathPointWithLaneId>>( |
62 | 63 | const std::vector<autoware_planning_msgs::msg::PathPointWithLaneId> &);
|
63 | 64 | extern template void validateNonEmpty<std::vector<autoware_planning_msgs::msg::TrajectoryPoint>>(
|
64 | 65 | const std::vector<autoware_planning_msgs::msg::TrajectoryPoint> &);
|
@@ -311,7 +312,8 @@ size_t findNearestIndex(const T & points, const geometry_msgs::msg::Point & poin
|
311 | 312 | extern template size_t findNearestIndex<std::vector<autoware_planning_msgs::msg::PathPoint>>(
|
312 | 313 | const std::vector<autoware_planning_msgs::msg::PathPoint> & points,
|
313 | 314 | const geometry_msgs::msg::Point & point);
|
314 |
| -extern template size_t findNearestIndex<std::vector<autoware_planning_msgs::msg::PathPointWithLaneId>>( |
| 315 | +extern template size_t |
| 316 | +findNearestIndex<std::vector<autoware_planning_msgs::msg::PathPointWithLaneId>>( |
315 | 317 | const std::vector<autoware_planning_msgs::msg::PathPointWithLaneId> & points,
|
316 | 318 | const geometry_msgs::msg::Point & point);
|
317 | 319 | extern template size_t findNearestIndex<std::vector<autoware_planning_msgs::msg::TrajectoryPoint>>(
|
@@ -463,8 +465,9 @@ calcLongitudinalOffsetToSegment<std::vector<autoware_planning_msgs::msg::PathPoi
|
463 | 465 | const geometry_msgs::msg::Point & p_target, const bool throw_exception = false);
|
464 | 466 | extern template double
|
465 | 467 | calcLongitudinalOffsetToSegment<std::vector<autoware_planning_msgs::msg::PathPointWithLaneId>>(
|
466 |
| - const std::vector<autoware_planning_msgs::msg::PathPointWithLaneId> & points, const size_t seg_idx, |
467 |
| - const geometry_msgs::msg::Point & p_target, const bool throw_exception = false); |
| 468 | + const std::vector<autoware_planning_msgs::msg::PathPointWithLaneId> & points, |
| 469 | + const size_t seg_idx, const geometry_msgs::msg::Point & p_target, |
| 470 | + const bool throw_exception = false); |
468 | 471 | extern template double
|
469 | 472 | calcLongitudinalOffsetToSegment<std::vector<autoware_planning_msgs::msg::TrajectoryPoint>>(
|
470 | 473 | const std::vector<autoware_planning_msgs::msg::TrajectoryPoint> & points, const size_t seg_idx,
|
@@ -734,8 +737,8 @@ extern template double calcSignedArcLength<std::vector<autoware_planning_msgs::m
|
734 | 737 | const size_t dst_idx);
|
735 | 738 | extern template double
|
736 | 739 | calcSignedArcLength<std::vector<autoware_planning_msgs::msg::PathPointWithLaneId>>(
|
737 |
| - const std::vector<autoware_planning_msgs::msg::PathPointWithLaneId> & points, const size_t src_idx, |
738 |
| - const size_t dst_idx); |
| 740 | + const std::vector<autoware_planning_msgs::msg::PathPointWithLaneId> & points, |
| 741 | + const size_t src_idx, const size_t dst_idx); |
739 | 742 | extern template double
|
740 | 743 | calcSignedArcLength<std::vector<autoware_planning_msgs::msg::TrajectoryPoint>>(
|
741 | 744 | const std::vector<autoware_planning_msgs::msg::TrajectoryPoint> & points, const size_t src_idx,
|
@@ -784,8 +787,8 @@ calcSignedArcLengthPartialSum<std::vector<autoware_planning_msgs::msg::PathPoint
|
784 | 787 | const size_t dst_idx);
|
785 | 788 | extern template std::vector<double>
|
786 | 789 | calcSignedArcLengthPartialSum<std::vector<autoware_planning_msgs::msg::PathPointWithLaneId>>(
|
787 |
| - const std::vector<autoware_planning_msgs::msg::PathPointWithLaneId> & points, const size_t src_idx, |
788 |
| - const size_t dst_idx); |
| 790 | + const std::vector<autoware_planning_msgs::msg::PathPointWithLaneId> & points, |
| 791 | + const size_t src_idx, const size_t dst_idx); |
789 | 792 | extern template std::vector<double>
|
790 | 793 | calcSignedArcLengthPartialSum<std::vector<autoware_planning_msgs::msg::TrajectoryPoint>>(
|
791 | 794 | const std::vector<autoware_planning_msgs::msg::TrajectoryPoint> & points, const size_t src_idx,
|
@@ -862,8 +865,8 @@ extern template double calcSignedArcLength<std::vector<autoware_planning_msgs::m
|
862 | 865 | const geometry_msgs::msg::Point & dst_point);
|
863 | 866 | extern template double
|
864 | 867 | calcSignedArcLength<std::vector<autoware_planning_msgs::msg::PathPointWithLaneId>>(
|
865 |
| - const std::vector<autoware_planning_msgs::msg::PathPointWithLaneId> & points, const size_t src_idx, |
866 |
| - const geometry_msgs::msg::Point & dst_point); |
| 868 | + const std::vector<autoware_planning_msgs::msg::PathPointWithLaneId> & points, |
| 869 | + const size_t src_idx, const geometry_msgs::msg::Point & dst_point); |
867 | 870 | extern template double
|
868 | 871 | calcSignedArcLength<std::vector<autoware_planning_msgs::msg::TrajectoryPoint>>(
|
869 | 872 | const std::vector<autoware_planning_msgs::msg::TrajectoryPoint> & points, const size_t src_idx,
|
@@ -1147,8 +1150,8 @@ calcLongitudinalOffsetPoint<std::vector<autoware_planning_msgs::msg::PathPoint>>
|
1147 | 1150 | const double offset, const bool throw_exception = false);
|
1148 | 1151 | extern template std::optional<geometry_msgs::msg::Point>
|
1149 | 1152 | calcLongitudinalOffsetPoint<std::vector<autoware_planning_msgs::msg::PathPointWithLaneId>>(
|
1150 |
| - const std::vector<autoware_planning_msgs::msg::PathPointWithLaneId> & points, const size_t src_idx, |
1151 |
| - const double offset, const bool throw_exception = false); |
| 1153 | + const std::vector<autoware_planning_msgs::msg::PathPointWithLaneId> & points, |
| 1154 | + const size_t src_idx, const double offset, const bool throw_exception = false); |
1152 | 1155 | extern template std::optional<geometry_msgs::msg::Point>
|
1153 | 1156 | calcLongitudinalOffsetPoint<std::vector<autoware_planning_msgs::msg::TrajectoryPoint>>(
|
1154 | 1157 | const std::vector<autoware_planning_msgs::msg::TrajectoryPoint> & points, const size_t src_idx,
|
@@ -1293,9 +1296,9 @@ calcLongitudinalOffsetPose<std::vector<autoware_planning_msgs::msg::PathPoint>>(
|
1293 | 1296 | const bool throw_exception = false);
|
1294 | 1297 | extern template std::optional<geometry_msgs::msg::Pose>
|
1295 | 1298 | calcLongitudinalOffsetPose<std::vector<autoware_planning_msgs::msg::PathPointWithLaneId>>(
|
1296 |
| - const std::vector<autoware_planning_msgs::msg::PathPointWithLaneId> & points, const size_t src_idx, |
1297 |
| - const double offset, const bool set_orientation_from_position_direction = true, |
1298 |
| - const bool throw_exception = false); |
| 1299 | + const std::vector<autoware_planning_msgs::msg::PathPointWithLaneId> & points, |
| 1300 | + const size_t src_idx, const double offset, |
| 1301 | + const bool set_orientation_from_position_direction = true, const bool throw_exception = false); |
1299 | 1302 | extern template std::optional<geometry_msgs::msg::Pose>
|
1300 | 1303 | calcLongitudinalOffsetPose<std::vector<autoware_planning_msgs::msg::TrajectoryPoint>>(
|
1301 | 1304 | const std::vector<autoware_planning_msgs::msg::TrajectoryPoint> & points, const size_t src_idx,
|
@@ -1906,7 +1909,8 @@ void insertOrientation(T & points, const bool is_driving_forward)
|
1906 | 1909 |
|
1907 | 1910 | extern template void insertOrientation<std::vector<autoware_planning_msgs::msg::PathPoint>>(
|
1908 | 1911 | std::vector<autoware_planning_msgs::msg::PathPoint> & points, const bool is_driving_forward);
|
1909 |
| -extern template void insertOrientation<std::vector<autoware_planning_msgs::msg::PathPointWithLaneId>>( |
| 1912 | +extern template void |
| 1913 | +insertOrientation<std::vector<autoware_planning_msgs::msg::PathPointWithLaneId>>( |
1910 | 1914 | std::vector<autoware_planning_msgs::msg::PathPointWithLaneId> & points,
|
1911 | 1915 | const bool is_driving_forward);
|
1912 | 1916 | extern template void insertOrientation<std::vector<autoware_planning_msgs::msg::TrajectoryPoint>>(
|
@@ -2051,8 +2055,8 @@ extern template double calcSignedArcLength<std::vector<autoware_planning_msgs::m
|
2051 | 2055 | const geometry_msgs::msg::Point & dst_point, const size_t dst_seg_idx);
|
2052 | 2056 | extern template double
|
2053 | 2057 | calcSignedArcLength<std::vector<autoware_planning_msgs::msg::PathPointWithLaneId>>(
|
2054 |
| - const std::vector<autoware_planning_msgs::msg::PathPointWithLaneId> & points, const size_t src_idx, |
2055 |
| - const geometry_msgs::msg::Point & dst_point, const size_t dst_seg_idx); |
| 2058 | + const std::vector<autoware_planning_msgs::msg::PathPointWithLaneId> & points, |
| 2059 | + const size_t src_idx, const geometry_msgs::msg::Point & dst_point, const size_t dst_seg_idx); |
2056 | 2060 | extern template double
|
2057 | 2061 | calcSignedArcLength<std::vector<autoware_planning_msgs::msg::TrajectoryPoint>>(
|
2058 | 2062 | const std::vector<autoware_planning_msgs::msg::TrajectoryPoint> & points, const size_t src_idx,
|
@@ -2460,7 +2464,8 @@ double calcYawDeviation(
|
2460 | 2464 | extern template double calcYawDeviation<std::vector<autoware_planning_msgs::msg::PathPoint>>(
|
2461 | 2465 | const std::vector<autoware_planning_msgs::msg::PathPoint> & points,
|
2462 | 2466 | const geometry_msgs::msg::Pose & pose, const bool throw_exception = false);
|
2463 |
| -extern template double calcYawDeviation<std::vector<autoware_planning_msgs::msg::PathPointWithLaneId>>( |
| 2467 | +extern template double |
| 2468 | +calcYawDeviation<std::vector<autoware_planning_msgs::msg::PathPointWithLaneId>>( |
2464 | 2469 | const std::vector<autoware_planning_msgs::msg::PathPointWithLaneId> & points,
|
2465 | 2470 | const geometry_msgs::msg::Pose & pose, const bool throw_exception = false);
|
2466 | 2471 | extern template double calcYawDeviation<std::vector<autoware_planning_msgs::msg::TrajectoryPoint>>(
|
@@ -2495,7 +2500,8 @@ extern template bool isTargetPointFront<std::vector<autoware_planning_msgs::msg:
|
2495 | 2500 | const std::vector<autoware_planning_msgs::msg::PathPoint> & points,
|
2496 | 2501 | const geometry_msgs::msg::Point & base_point, const geometry_msgs::msg::Point & target_point,
|
2497 | 2502 | const double threshold = 0.0);
|
2498 |
| -extern template bool isTargetPointFront<std::vector<autoware_planning_msgs::msg::PathPointWithLaneId>>( |
| 2503 | +extern template bool |
| 2504 | +isTargetPointFront<std::vector<autoware_planning_msgs::msg::PathPointWithLaneId>>( |
2499 | 2505 | const std::vector<autoware_planning_msgs::msg::PathPointWithLaneId> & points,
|
2500 | 2506 | const geometry_msgs::msg::Point & base_point, const geometry_msgs::msg::Point & target_point,
|
2501 | 2507 | const double threshold = 0.0);
|
|
0 commit comments