12
12
// See the License for the specific language governing permissions and
13
13
// limitations under the License.
14
14
15
- #include " autoware/motion_utils/trajectory_container/ trajectory/trajectory_path_point .hpp"
15
+ #include " autoware/trajectory/path_point .hpp"
16
16
17
17
#include < autoware_planning_msgs/msg/path_point.hpp>
18
18
#include < geometry_msgs/msg/point.hpp>
21
21
22
22
#include < vector>
23
23
24
- autoware_planning_msgs::msg::PathPoint pose (double x, double y)
24
+ autoware_planning_msgs::msg::PathPoint path_point (double x, double y)
25
25
{
26
26
autoware_planning_msgs::msg::PathPoint p;
27
27
p.pose .position .x = x;
@@ -32,18 +32,20 @@ autoware_planning_msgs::msg::PathPoint pose(double x, double y)
32
32
33
33
int main ()
34
34
{
35
- using autoware::motion_utils::trajectory_container:: trajectory::TrajectoryContainer ;
35
+ using autoware::trajectory::Trajectory ;
36
36
37
37
pybind11::scoped_interpreter guard{};
38
38
39
39
auto plt = matplotlibcpp17::pyplot::import ();
40
40
41
41
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 )};
47
49
48
50
{
49
51
std::vector<double > x;
@@ -57,8 +59,7 @@ int main()
57
59
plt.scatter (Args (x, y), Kwargs (" label" _a = " Original" , " color" _a = " red" ));
58
60
}
59
61
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);
62
63
63
64
if (!trajectory) {
64
65
std::cerr << " Failed to build trajectory" << std::endl;
0 commit comments