Skip to content

Commit 1aaf19a

Browse files
Merge pull request #1801 from tier4/beta-to-tier4-main-sync
chore: sync beta branch beta/v0.41 with tier4/main
2 parents c5f0a24 + f6dd2bd commit 1aaf19a

File tree

369 files changed

+13595
-2539
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

369 files changed

+13595
-2539
lines changed

build_depends.repos

+1-1
Original file line numberDiff line numberDiff line change
@@ -32,7 +32,7 @@ repositories:
3232
core/autoware_internal_msgs:
3333
type: git
3434
url: https://github.com/autowarefoundation/autoware_internal_msgs.git
35-
version: 1.3.0
35+
version: 1.5.0
3636
# universe
3737
universe/external/tier4_autoware_msgs:
3838
type: git

common/autoware_motion_utils/README.md

+1-1
Original file line numberDiff line numberDiff line change
@@ -47,7 +47,7 @@ The second function finds the nearest index in the lane whose id is `lane_id`.
4747
4848
```cpp
4949
size_t findNearestIndexFromLaneId(
50-
const tier4_planning_msgs::msg::PathWithLaneId & path,
50+
const autoware_internal_planning_msgs::msg::PathWithLaneId & path,
5151
const geometry_msgs::msg::Point & pos, const int64_t lane_id);
5252
```
5353

common/autoware_motion_utils/include/autoware/motion_utils/resample/resample.hpp

+8-7
Original file line numberDiff line numberDiff line change
@@ -15,9 +15,9 @@
1515
#ifndef AUTOWARE__MOTION_UTILS__RESAMPLE__RESAMPLE_HPP_
1616
#define AUTOWARE__MOTION_UTILS__RESAMPLE__RESAMPLE_HPP_
1717

18+
#include "autoware_internal_planning_msgs/msg/path_with_lane_id.hpp"
1819
#include "autoware_planning_msgs/msg/path.hpp"
1920
#include "autoware_planning_msgs/msg/trajectory.hpp"
20-
#include "tier4_planning_msgs/msg/path_with_lane_id.hpp"
2121

2222
#include <vector>
2323

@@ -113,8 +113,8 @@ std::vector<geometry_msgs::msg::Pose> resamplePoseVector(
113113
* longitudinal and lateral velocity. Otherwise, it uses linear interpolation
114114
* @return resampled path
115115
*/
116-
tier4_planning_msgs::msg::PathWithLaneId resamplePath(
117-
const tier4_planning_msgs::msg::PathWithLaneId & input_path,
116+
autoware_internal_planning_msgs::msg::PathWithLaneId resamplePath(
117+
const autoware_internal_planning_msgs::msg::PathWithLaneId & input_path,
118118
const std::vector<double> & resampled_arclength, const bool use_akima_spline_for_xy = false,
119119
const bool use_lerp_for_z = true, const bool use_zero_order_hold_for_v = true);
120120

@@ -136,10 +136,11 @@ tier4_planning_msgs::msg::PathWithLaneId resamplePath(
136136
* @param resample_input_path_stop_point If true, resample closest stop point in input path
137137
* @return resampled path
138138
*/
139-
tier4_planning_msgs::msg::PathWithLaneId resamplePath(
140-
const tier4_planning_msgs::msg::PathWithLaneId & input_path, const double resample_interval,
141-
const bool use_akima_spline_for_xy = false, const bool use_lerp_for_z = true,
142-
const bool use_zero_order_hold_for_v = true, const bool resample_input_path_stop_point = true);
139+
autoware_internal_planning_msgs::msg::PathWithLaneId resamplePath(
140+
const autoware_internal_planning_msgs::msg::PathWithLaneId & input_path,
141+
const double resample_interval, const bool use_akima_spline_for_xy = false,
142+
const bool use_lerp_for_z = true, const bool use_zero_order_hold_for_v = true,
143+
const bool resample_input_path_stop_point = true);
143144

144145
/**
145146
* @brief A resampling function for a path. Note that in a default setting, position xy are

common/autoware_motion_utils/include/autoware/motion_utils/trajectory/conversion.hpp

+8-7
Original file line numberDiff line numberDiff line change
@@ -15,11 +15,11 @@
1515
#ifndef AUTOWARE__MOTION_UTILS__TRAJECTORY__CONVERSION_HPP_
1616
#define AUTOWARE__MOTION_UTILS__TRAJECTORY__CONVERSION_HPP_
1717

18+
#include "autoware_internal_planning_msgs/msg/detail/path_with_lane_id__struct.hpp"
1819
#include "autoware_planning_msgs/msg/detail/path__struct.hpp"
1920
#include "autoware_planning_msgs/msg/detail/trajectory__struct.hpp"
2021
#include "autoware_planning_msgs/msg/detail/trajectory_point__struct.hpp"
2122
#include "std_msgs/msg/header.hpp"
22-
#include "tier4_planning_msgs/msg/detail/path_with_lane_id__struct.hpp"
2323

2424
#include <vector>
2525

@@ -58,7 +58,7 @@ autoware_planning_msgs::msg::Path convertToPath([[maybe_unused]] const T & input
5858

5959
template <>
6060
inline autoware_planning_msgs::msg::Path convertToPath(
61-
const tier4_planning_msgs::msg::PathWithLaneId & input)
61+
const autoware_internal_planning_msgs::msg::PathWithLaneId & input)
6262
{
6363
autoware_planning_msgs::msg::Path output{};
6464
output.header = input.header;
@@ -80,7 +80,7 @@ TrajectoryPoints convertToTrajectoryPoints([[maybe_unused]] const T & input)
8080

8181
template <>
8282
inline TrajectoryPoints convertToTrajectoryPoints(
83-
const tier4_planning_msgs::msg::PathWithLaneId & input)
83+
const autoware_internal_planning_msgs::msg::PathWithLaneId & input)
8484
{
8585
TrajectoryPoints output{};
8686
for (const auto & p : input.points) {
@@ -95,19 +95,20 @@ inline TrajectoryPoints convertToTrajectoryPoints(
9595
}
9696

9797
template <class T>
98-
tier4_planning_msgs::msg::PathWithLaneId convertToPathWithLaneId([[maybe_unused]] const T & input)
98+
autoware_internal_planning_msgs::msg::PathWithLaneId convertToPathWithLaneId(
99+
[[maybe_unused]] const T & input)
99100
{
100101
static_assert(sizeof(T) == 0, "Only specializations of convertToPathWithLaneId can be used.");
101102
throw std::logic_error("Only specializations of convertToPathWithLaneId can be used.");
102103
}
103104

104105
template <>
105-
inline tier4_planning_msgs::msg::PathWithLaneId convertToPathWithLaneId(
106+
inline autoware_internal_planning_msgs::msg::PathWithLaneId convertToPathWithLaneId(
106107
const TrajectoryPoints & input)
107108
{
108-
tier4_planning_msgs::msg::PathWithLaneId output{};
109+
autoware_internal_planning_msgs::msg::PathWithLaneId output{};
109110
for (const auto & p : input) {
110-
tier4_planning_msgs::msg::PathPointWithLaneId pp;
111+
autoware_internal_planning_msgs::msg::PathPointWithLaneId pp;
111112
pp.point.pose = p.pose;
112113
pp.point.longitudinal_velocity_mps = p.longitudinal_velocity_mps;
113114
output.points.emplace_back(pp);

common/autoware_motion_utils/include/autoware/motion_utils/trajectory/interpolation.hpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -17,8 +17,8 @@
1717

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

20+
#include "autoware_internal_planning_msgs/msg/path_with_lane_id.hpp"
2021
#include "autoware_planning_msgs/msg/trajectory.hpp"
21-
#include "tier4_planning_msgs/msg/path_with_lane_id.hpp"
2222

2323
#include <boost/optional.hpp>
2424

@@ -51,8 +51,8 @@ autoware_planning_msgs::msg::TrajectoryPoint calcInterpolatedPoint(
5151
* twist information
5252
* @return resampled path(poses)
5353
*/
54-
tier4_planning_msgs::msg::PathPointWithLaneId calcInterpolatedPoint(
55-
const tier4_planning_msgs::msg::PathWithLaneId & path,
54+
autoware_internal_planning_msgs::msg::PathPointWithLaneId calcInterpolatedPoint(
55+
const autoware_internal_planning_msgs::msg::PathWithLaneId & path,
5656
const geometry_msgs::msg::Pose & target_pose, const bool use_zero_order_hold_for_twist = false,
5757
const double dist_threshold = std::numeric_limits<double>::max(),
5858
const double yaw_threshold = std::numeric_limits<double>::max());

common/autoware_motion_utils/include/autoware/motion_utils/trajectory/path_with_lane_id.hpp

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

18-
#include "tier4_planning_msgs/msg/path_with_lane_id.hpp"
18+
#include "autoware_internal_planning_msgs/msg/path_with_lane_id.hpp"
1919
#include <geometry_msgs/msg/point.hpp>
2020

2121
#include <optional>
2222
#include <utility>
2323
namespace autoware::motion_utils
2424
{
2525
std::optional<std::pair<size_t, size_t>> getPathIndexRangeWithLaneId(
26-
const tier4_planning_msgs::msg::PathWithLaneId & path, const int64_t target_lane_id);
26+
const autoware_internal_planning_msgs::msg::PathWithLaneId & path, const int64_t target_lane_id);
2727

2828
size_t findNearestIndexFromLaneId(
29-
const tier4_planning_msgs::msg::PathWithLaneId & path, const geometry_msgs::msg::Point & pos,
30-
const int64_t lane_id);
29+
const autoware_internal_planning_msgs::msg::PathWithLaneId & path,
30+
const geometry_msgs::msg::Point & pos, const int64_t lane_id);
3131

3232
size_t findNearestSegmentIndexFromLaneId(
33-
const tier4_planning_msgs::msg::PathWithLaneId & path, const geometry_msgs::msg::Point & pos,
34-
const int64_t lane_id);
33+
const autoware_internal_planning_msgs::msg::PathWithLaneId & path,
34+
const geometry_msgs::msg::Point & pos, const int64_t lane_id);
3535

3636
// @brief Calculates the path to be followed by the rear wheel center in order to make the vehicle
3737
// center follow the input path
3838
// @param [in] path with position to be followed by the center of the vehicle
3939
// @param [out] PathWithLaneId to be followed by the rear wheel center follow to make the vehicle
4040
// center follow the input path NOTE: rear_to_cog is supposed to be positive
41-
tier4_planning_msgs::msg::PathWithLaneId convertToRearWheelCenter(
42-
const tier4_planning_msgs::msg::PathWithLaneId & path, const double rear_to_cog,
41+
autoware_internal_planning_msgs::msg::PathWithLaneId convertToRearWheelCenter(
42+
const autoware_internal_planning_msgs::msg::PathWithLaneId & path, const double rear_to_cog,
4343
const bool enable_last_point_compensation = true);
4444
} // namespace autoware::motion_utils
4545

0 commit comments

Comments
 (0)