diff --git a/autoware_planning_msgs/CMakeLists.txt b/autoware_planning_msgs/CMakeLists.txt index 333c1a8..156dd80 100644 --- a/autoware_planning_msgs/CMakeLists.txt +++ b/autoware_planning_msgs/CMakeLists.txt @@ -9,10 +9,18 @@ rosidl_generate_interfaces(${PROJECT_NAME} "msg/LaneletRoute.msg" "msg/LaneletSegment.msg" "msg/PoseWithUuidStamped.msg" + "msg/Trajectory.msg" + "msg/TrajectoryPoint.msg" + "msg/Path.msg" + "msg/PathPoint.msg" + "msg/PathWithLaneId.msg" + "msg/PathPointWithLaneId.msg" DEPENDENCIES geometry_msgs std_msgs unique_identifier_msgs + nav_msgs + builtin_interfaces ADD_LINTER_TESTS ) diff --git a/autoware_planning_msgs/msg/Path.msg b/autoware_planning_msgs/msg/Path.msg new file mode 100644 index 0000000..91633ff --- /dev/null +++ b/autoware_planning_msgs/msg/Path.msg @@ -0,0 +1,4 @@ +std_msgs/Header header +autoware_planning_msgs/PathPoint[] points +geometry_msgs/Point[] left_bound +geometry_msgs/Point[] right_bound diff --git a/autoware_planning_msgs/msg/PathPoint.msg b/autoware_planning_msgs/msg/PathPoint.msg new file mode 100644 index 0000000..697681f --- /dev/null +++ b/autoware_planning_msgs/msg/PathPoint.msg @@ -0,0 +1,5 @@ +geometry_msgs/Pose pose +float32 longitudinal_velocity_mps +float32 lateral_velocity_mps +float32 heading_rate_rps +bool is_final diff --git a/autoware_planning_msgs/msg/PathPointWithLaneId.msg b/autoware_planning_msgs/msg/PathPointWithLaneId.msg new file mode 100644 index 0000000..19eea9f --- /dev/null +++ b/autoware_planning_msgs/msg/PathPointWithLaneId.msg @@ -0,0 +1,2 @@ +autoware_planning_msgs/PathPoint point +int64[] lane_ids diff --git a/autoware_planning_msgs/msg/PathWithLaneId.msg b/autoware_planning_msgs/msg/PathWithLaneId.msg new file mode 100644 index 0000000..4041d78 --- /dev/null +++ b/autoware_planning_msgs/msg/PathWithLaneId.msg @@ -0,0 +1,4 @@ +std_msgs/Header header +autoware_planning_msgs/PathPointWithLaneId[] points +geometry_msgs/Point[] left_bound +geometry_msgs/Point[] right_bound diff --git a/autoware_planning_msgs/msg/Trajectory.msg b/autoware_planning_msgs/msg/Trajectory.msg new file mode 100644 index 0000000..3adafba --- /dev/null +++ b/autoware_planning_msgs/msg/Trajectory.msg @@ -0,0 +1,3 @@ +uint32 CAPACITY = 10000 +std_msgs/Header header +autoware_planning_msgs/TrajectoryPoint[10000] points diff --git a/autoware_planning_msgs/msg/TrajectoryPoint.msg b/autoware_planning_msgs/msg/TrajectoryPoint.msg new file mode 100644 index 0000000..613ae4c --- /dev/null +++ b/autoware_planning_msgs/msg/TrajectoryPoint.msg @@ -0,0 +1,8 @@ +builtin_interfaces/Duration time_from_start +geometry_msgs/Pose pose +float32 longitudinal_velocity_mps +float32 lateral_velocity_mps +float32 acceleration_mps2 +float32 heading_rate_rps +float32 front_wheel_angle_rad +float32 rear_wheel_angle_rad diff --git a/autoware_planning_msgs/package.xml b/autoware_planning_msgs/package.xml index d186898..e0ad5fd 100644 --- a/autoware_planning_msgs/package.xml +++ b/autoware_planning_msgs/package.xml @@ -11,7 +11,9 @@ rosidl_default_generators + builtin_interfaces geometry_msgs + nav_msgs std_msgs unique_identifier_msgs