Skip to content

Commit ca115d6

Browse files
feat(autoware_trajectory): move trajectory_container from autoware_motion_utils to a new package (#9253)
* create trajectory container package Signed-off-by: Y.Hisaki <yhisaki31@gmail.com> * update Signed-off-by: Y.Hisaki <yhisaki31@gmail.com> * update Signed-off-by: Y.Hisaki <yhisaki31@gmail.com> * style(pre-commit): autofix * update codeowner Signed-off-by: Y.Hisaki <yhisaki31@gmail.com> * update Signed-off-by: Y.Hisaki <yhisaki31@gmail.com> * fix cmake Signed-off-by: Y.Hisaki <yhisaki31@gmail.com> --------- Signed-off-by: Y.Hisaki <yhisaki31@gmail.com> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
1 parent 6c4de54 commit ca115d6

40 files changed

+439
-374
lines changed

.github/CODEOWNERS

+1
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,7 @@ common/autoware_signal_processing/** ali.boyali@tier4.jp fumiya.watanabe@tier4.j
2222
common/autoware_test_utils/** kyoichi.sugahara@tier4.jp mamoru.sobue@tier4.jp takamasa.horibe@tier4.jp zulfaqar.azmi@tier4.jp
2323
common/autoware_testing/** adam.dabrowski@robotec.ai satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp
2424
common/autoware_time_utils/** christopherj.ho@gmail.com shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp
25+
common/autoware_trajectory_container/** yukinari.hisaki.2@tier4.jp takayuki.murooka@tier4.jp mamoru.sobue@tier4.jp
2526
common/autoware_universe_utils/** mamoru.sobue@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp
2627
common/autoware_vehicle_info_utils/** mamoru.sobue@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp
2728
common/bag_time_manager_rviz_plugin/** taiki.tanaka@tier4.jp
Original file line numberDiff line numberDiff line change
@@ -1,8 +1,6 @@
11
cmake_minimum_required(VERSION 3.14)
22
project(autoware_motion_utils)
33

4-
option(BUILD_EXAMPLES "Build examples" OFF)
5-
64
find_package(autoware_cmake REQUIRED)
75
autoware_package()
86

@@ -24,28 +22,4 @@ if(BUILD_TESTING)
2422
)
2523
endif()
2624

27-
if(BUILD_EXAMPLES)
28-
message(STATUS "Building examples")
29-
30-
include(FetchContent)
31-
fetchcontent_declare(
32-
matplotlibcpp17
33-
GIT_REPOSITORY https://github.com/soblin/matplotlibcpp17.git
34-
GIT_TAG master
35-
)
36-
fetchcontent_makeavailable(matplotlibcpp17)
37-
38-
file(GLOB_RECURSE example_files examples/*.cpp)
39-
40-
foreach(example_file ${example_files})
41-
get_filename_component(example_name ${example_file} NAME_WE)
42-
ament_auto_add_executable(${example_name} ${example_file})
43-
set_source_files_properties(${example_file} PROPERTIES COMPILE_FLAGS -Wno-error -Wno-attributes -Wno-unused-parameter)
44-
target_link_libraries(${example_name}
45-
autoware_motion_utils
46-
matplotlibcpp17::matplotlibcpp17
47-
)
48-
endforeach()
49-
endif()
50-
5125
ament_auto_package()

common/autoware_motion_utils/include/autoware/motion_utils/trajectory_container/interpolator.hpp

-23
This file was deleted.

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

-21
This file was deleted.

common/autoware_motion_utils/package.xml

-1
Original file line numberDiff line numberDiff line change
@@ -34,7 +34,6 @@
3434
<depend>tf2_geometry_msgs</depend>
3535
<depend>tier4_planning_msgs</depend>
3636
<depend>visualization_msgs</depend>
37-
<!-- <depend>lanelet2_core</depend> -->
3837

3938
<test_depend>ament_cmake_ros</test_depend>
4039
<test_depend>ament_lint_auto</test_depend>
+50
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,50 @@
1+
cmake_minimum_required(VERSION 3.14)
2+
3+
project(autoware_trajectory)
4+
5+
option(BUILD_EXAMPLES "Build examples" OFF)
6+
7+
find_package(autoware_cmake REQUIRED)
8+
autoware_package()
9+
10+
ament_auto_add_library(autoware_trajectory SHARED
11+
DIRECTORY src
12+
)
13+
14+
if(BUILD_TESTING)
15+
find_package(ament_cmake_ros REQUIRED)
16+
17+
file(GLOB_RECURSE test_files test/*.cpp)
18+
19+
ament_add_ros_isolated_gtest(test_autoware_trajectory ${test_files})
20+
21+
target_link_libraries(test_autoware_trajectory
22+
autoware_trajectory
23+
)
24+
endif()
25+
26+
if(BUILD_EXAMPLES)
27+
message(STATUS "Building examples")
28+
29+
include(FetchContent)
30+
fetchcontent_declare(
31+
matplotlibcpp17
32+
GIT_REPOSITORY https://github.com/soblin/matplotlibcpp17.git
33+
GIT_TAG master
34+
)
35+
fetchcontent_makeavailable(matplotlibcpp17)
36+
37+
file(GLOB_RECURSE example_files examples/*.cpp)
38+
39+
foreach(example_file ${example_files})
40+
get_filename_component(example_name ${example_file} NAME_WE)
41+
ament_auto_add_executable(${example_name} ${example_file})
42+
set_source_files_properties(${example_file} PROPERTIES COMPILE_FLAGS -Wno-error -Wno-attributes -Wno-unused-parameter)
43+
target_link_libraries(${example_name}
44+
autoware_trajectory
45+
matplotlibcpp17::matplotlibcpp17
46+
)
47+
endforeach()
48+
endif()
49+
50+
ament_auto_package()

common/autoware_trajectory/README.md

+64
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,64 @@
1+
# Autoware Trajectory
2+
3+
This package provides classes to manage/manipulate Trajectory.
4+
5+
## Example Usage
6+
7+
This section describes Example Usage of `Trajectory<autoware_planning_msgs::msg::PathPoint>`
8+
9+
- Load Trajectory from point array
10+
11+
```cpp
12+
#include "autoware/trajectory/path_point.hpp"
13+
14+
...
15+
16+
std::vector<autoware_planning_msgs::msg::PathPoint> points = ... // Load points from somewhere
17+
18+
using autoware::trajectory::Trajectory;
19+
20+
std::optional<Trajectory<autoware_planning_msgs::msg::PathPoint>> trajectory =
21+
Trajectory<autoware_planning_msgs::msg::PathPoint>::Builder{}
22+
.build(points);
23+
```
24+
25+
- You can also specify interpolation method
26+
27+
```cpp
28+
using autoware::trajectory::interpolator::CubicSpline;
29+
30+
std::optional<Trajectory<autoware_planning_msgs::msg::PathPoint>> trajectory =
31+
Trajectory<autoware_planning_msgs::msg::PathPoint>::Builder{}
32+
.set_xy_interpolator<CubicSpline>() // Set interpolator for x-y plane
33+
.build(points);
34+
```
35+
36+
- Access point on Trajectory
37+
38+
```cpp
39+
autoware_planning_msgs::msg::PathPoint point = trajectory->compute(1.0); // Get point at s=0.0. s is distance from start point on Trajectory.
40+
```
41+
42+
- Get length of Trajectory
43+
44+
```cpp
45+
double length = trajectory->length();
46+
```
47+
48+
- Set 3.0[m] ~ 5.0[m] part of velocity to 0.0
49+
50+
```cpp
51+
trajectory->longitudinal_velocity_mps(3.0, 5.0) = 0.0;
52+
```
53+
54+
- Crop Trajectory from 1.0[m] to 2.0[m]
55+
56+
```cpp
57+
trajectory->crop(1.0, 2.0);
58+
```
59+
60+
- Restore points
61+
62+
```cpp
63+
std::vector<autoware_planning_msgs::msg::PathPoint> points = trajectory->restore();
64+
```

common/autoware_motion_utils/examples/example_interpolator.cpp common/autoware_trajectory/examples/example_interpolator.cpp

+12-12
Original file line numberDiff line numberDiff line change
@@ -12,12 +12,12 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#include "autoware/motion_utils/trajectory_container/interpolator/akima_spline.hpp"
16-
#include "autoware/motion_utils/trajectory_container/interpolator/cubic_spline.hpp"
17-
#include "autoware/motion_utils/trajectory_container/interpolator/interpolator.hpp"
18-
#include "autoware/motion_utils/trajectory_container/interpolator/linear.hpp"
19-
#include "autoware/motion_utils/trajectory_container/interpolator/nearest_neighbor.hpp"
20-
#include "autoware/motion_utils/trajectory_container/interpolator/stairstep.hpp"
15+
#include "autoware/trajectory/interpolator/akima_spline.hpp"
16+
#include "autoware/trajectory/interpolator/cubic_spline.hpp"
17+
#include "autoware/trajectory/interpolator/interpolator.hpp"
18+
#include "autoware/trajectory/interpolator/linear.hpp"
19+
#include "autoware/trajectory/interpolator/nearest_neighbor.hpp"
20+
#include "autoware/trajectory/interpolator/stairstep.hpp"
2121

2222
#include <matplotlibcpp17/pyplot.h>
2323

@@ -41,10 +41,10 @@ int main()
4141
// Scatter Data
4242
plt.scatter(Args(bases, values));
4343

44-
using autoware::motion_utils::trajectory_container::interpolator::InterpolatorInterface;
44+
using autoware::trajectory::interpolator::InterpolatorInterface;
4545
// Linear Interpolator
4646
{
47-
using autoware::motion_utils::trajectory_container::interpolator::Linear;
47+
using autoware::trajectory::interpolator::Linear;
4848
auto interpolator = *Linear::Builder{}.set_bases(bases).set_values(values).build();
4949
std::vector<double> x;
5050
std::vector<double> y;
@@ -57,7 +57,7 @@ int main()
5757

5858
// AkimaSpline Interpolator
5959
{
60-
using autoware::motion_utils::trajectory_container::interpolator::AkimaSpline;
60+
using autoware::trajectory::interpolator::AkimaSpline;
6161

6262
auto interpolator = *AkimaSpline::Builder{}.set_bases(bases).set_values(values).build();
6363
std::vector<double> x;
@@ -71,7 +71,7 @@ int main()
7171

7272
// CubicSpline Interpolator
7373
{
74-
using autoware::motion_utils::trajectory_container::interpolator::CubicSpline;
74+
using autoware::trajectory::interpolator::CubicSpline;
7575
auto interpolator = *CubicSpline::Builder{}.set_bases(bases).set_values(values).build();
7676
std::vector<double> x;
7777
std::vector<double> y;
@@ -84,7 +84,7 @@ int main()
8484

8585
// NearestNeighbor Interpolator
8686
{
87-
using autoware::motion_utils::trajectory_container::interpolator::NearestNeighbor;
87+
using autoware::trajectory::interpolator::NearestNeighbor;
8888
auto interpolator =
8989
*NearestNeighbor<double>::Builder{}.set_bases(bases).set_values(values).build();
9090
std::vector<double> x;
@@ -98,7 +98,7 @@ int main()
9898

9999
// Stairstep Interpolator
100100
{
101-
using autoware::motion_utils::trajectory_container::interpolator::Stairstep;
101+
using autoware::trajectory::interpolator::Stairstep;
102102
auto interpolator = *Stairstep<double>::Builder{}.set_bases(bases).set_values(values).build();
103103
std::vector<double> x;
104104
std::vector<double> y;

common/autoware_motion_utils/examples/example_trajectory_path_point.cpp common/autoware_trajectory/examples/example_trajectory_path_point.cpp

+11-10
Original file line numberDiff line numberDiff line change
@@ -12,7 +12,7 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#include "autoware/motion_utils/trajectory_container/trajectory/trajectory_path_point.hpp"
15+
#include "autoware/trajectory/path_point.hpp"
1616

1717
#include <autoware_planning_msgs/msg/path_point.hpp>
1818
#include <geometry_msgs/msg/point.hpp>
@@ -21,7 +21,7 @@
2121

2222
#include <vector>
2323

24-
autoware_planning_msgs::msg::PathPoint pose(double x, double y)
24+
autoware_planning_msgs::msg::PathPoint path_point(double x, double y)
2525
{
2626
autoware_planning_msgs::msg::PathPoint p;
2727
p.pose.position.x = x;
@@ -32,18 +32,20 @@ autoware_planning_msgs::msg::PathPoint pose(double x, double y)
3232

3333
int main()
3434
{
35-
using autoware::motion_utils::trajectory_container::trajectory::TrajectoryContainer;
35+
using autoware::trajectory::Trajectory;
3636

3737
pybind11::scoped_interpreter guard{};
3838

3939
auto plt = matplotlibcpp17::pyplot::import();
4040

4141
std::vector<autoware_planning_msgs::msg::PathPoint> points = {
42-
pose(0.49, 0.59), pose(0.61, 1.22), pose(0.86, 1.93), pose(1.20, 2.56), pose(1.51, 3.17),
43-
pose(1.85, 3.76), pose(2.14, 4.26), pose(2.60, 4.56), pose(3.07, 4.55), pose(3.61, 4.30),
44-
pose(3.95, 4.01), pose(4.29, 3.68), pose(4.90, 3.25), pose(5.54, 3.10), pose(6.24, 3.18),
45-
pose(6.88, 3.54), pose(7.51, 4.25), pose(7.85, 4.93), pose(8.03, 5.73), pose(8.16, 6.52),
46-
pose(8.31, 7.28), pose(8.45, 7.93), pose(8.68, 8.45), pose(8.96, 8.96), pose(9.32, 9.36)};
42+
path_point(0.49, 0.59), path_point(0.61, 1.22), path_point(0.86, 1.93), path_point(1.20, 2.56),
43+
path_point(1.51, 3.17), path_point(1.85, 3.76), path_point(2.14, 4.26), path_point(2.60, 4.56),
44+
path_point(3.07, 4.55), path_point(3.61, 4.30), path_point(3.95, 4.01), path_point(4.29, 3.68),
45+
path_point(4.90, 3.25), path_point(5.54, 3.10), path_point(6.24, 3.18), path_point(6.88, 3.54),
46+
path_point(7.51, 4.25), path_point(7.85, 4.93), path_point(8.03, 5.73), path_point(8.16, 6.52),
47+
path_point(8.31, 7.28), path_point(8.45, 7.93), path_point(8.68, 8.45), path_point(8.96, 8.96),
48+
path_point(9.32, 9.36)};
4749

4850
{
4951
std::vector<double> x;
@@ -57,8 +59,7 @@ int main()
5759
plt.scatter(Args(x, y), Kwargs("label"_a = "Original", "color"_a = "red"));
5860
}
5961

60-
auto trajectory =
61-
TrajectoryContainer<autoware_planning_msgs::msg::PathPoint>::Builder{}.build(points);
62+
auto trajectory = Trajectory<autoware_planning_msgs::msg::PathPoint>::Builder{}.build(points);
6263

6364
if (!trajectory) {
6465
std::cerr << "Failed to build trajectory" << std::endl;

common/autoware_motion_utils/examples/example_trajectory_point.cpp common/autoware_trajectory/examples/example_trajectory_point.cpp

+5-5
Original file line numberDiff line numberDiff line change
@@ -12,8 +12,8 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#include "autoware/motion_utils/trajectory_container/interpolator/cubic_spline.hpp"
16-
#include "autoware/motion_utils/trajectory_container/trajectory/trajectory_point.hpp"
15+
#include "autoware/trajectory/interpolator/cubic_spline.hpp"
16+
#include "autoware/trajectory/point.hpp"
1717

1818
#include <geometry_msgs/msg/point.hpp>
1919

@@ -55,10 +55,10 @@ int main()
5555
plt.scatter(Args(x, y), Kwargs("label"_a = "Original", "color"_a = "red"));
5656
}
5757

58-
using autoware::motion_utils::trajectory_container::interpolator::CubicSpline;
59-
using autoware::motion_utils::trajectory_container::trajectory::TrajectoryContainer;
58+
using autoware::trajectory::Trajectory;
59+
using autoware::trajectory::interpolator::CubicSpline;
6060

61-
auto trajectory = TrajectoryContainer<geometry_msgs::msg::Point>::Builder()
61+
auto trajectory = Trajectory<geometry_msgs::msg::Point>::Builder()
6262
.set_xy_interpolator<CubicSpline>()
6363
.set_z_interpolator<CubicSpline>()
6464
.build(points);

common/autoware_motion_utils/examples/example_trajectory_pose.cpp common/autoware_trajectory/examples/example_trajectory_pose.cpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -12,7 +12,7 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#include "autoware/motion_utils/trajectory_container/trajectory/trajectory_pose.hpp"
15+
#include "autoware/trajectory/pose.hpp"
1616

1717
#include <geometry_msgs/msg/pose.hpp>
1818

@@ -44,10 +44,10 @@ int main()
4444
pose(6.88, 3.54), pose(7.51, 4.25), pose(7.85, 4.93), pose(8.03, 5.73), pose(8.16, 6.52),
4545
pose(8.31, 7.28), pose(8.45, 7.93), pose(8.68, 8.45), pose(8.96, 8.96), pose(9.32, 9.36)};
4646

47-
using autoware::motion_utils::trajectory_container::interpolator::CubicSpline;
48-
using autoware::motion_utils::trajectory_container::trajectory::TrajectoryContainer;
47+
using autoware::trajectory::Trajectory;
48+
using autoware::trajectory::interpolator::CubicSpline;
4949

50-
auto trajectory = TrajectoryContainer<geometry_msgs::msg::Pose>::Builder{}.build(poses);
50+
auto trajectory = Trajectory<geometry_msgs::msg::Pose>::Builder{}.build(poses);
5151

5252
trajectory->align_orientation_with_trajectory_direction();
5353

0 commit comments

Comments
 (0)