From ae63d7a793216e2555ac7a62c9a21abbb9f3efd9 Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" Date: Tue, 23 Jan 2024 23:26:41 +0900 Subject: [PATCH] feat(autoware_planning_msgs): add route services Signed-off-by: Takagi, Isamu --- autoware_planning_msgs/CMakeLists.txt | 16 ++++++++++------ autoware_planning_msgs/msg/RouteState.msg | 11 +++++++++++ autoware_planning_msgs/package.xml | 2 +- autoware_planning_msgs/srv/ClearRoute.srv | 2 ++ autoware_planning_msgs/srv/SetLaneletRoute.srv | 11 +++++++++++ autoware_planning_msgs/srv/SetWaypointRoute.srv | 11 +++++++++++ 6 files changed, 46 insertions(+), 7 deletions(-) create mode 100644 autoware_planning_msgs/msg/RouteState.msg create mode 100644 autoware_planning_msgs/srv/ClearRoute.srv create mode 100644 autoware_planning_msgs/srv/SetLaneletRoute.srv create mode 100644 autoware_planning_msgs/srv/SetWaypointRoute.srv diff --git a/autoware_planning_msgs/CMakeLists.txt b/autoware_planning_msgs/CMakeLists.txt index 156dd80..d9634eb 100644 --- a/autoware_planning_msgs/CMakeLists.txt +++ b/autoware_planning_msgs/CMakeLists.txt @@ -8,19 +8,23 @@ rosidl_generate_interfaces(${PROJECT_NAME} "msg/LaneletPrimitive.msg" "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" + "msg/PathWithLaneId.msg" + "msg/PoseWithUuidStamped.msg" + "msg/RouteState.msg" + "msg/Trajectory.msg" + "msg/TrajectoryPoint.msg" + "srv/ClearRoute.srv" + "srv/SetLaneletRoute.srv" + "srv/SetWaypointRoute.srv" DEPENDENCIES + autoware_common_msgs + builtin_interfaces geometry_msgs std_msgs unique_identifier_msgs - nav_msgs - builtin_interfaces ADD_LINTER_TESTS ) diff --git a/autoware_planning_msgs/msg/RouteState.msg b/autoware_planning_msgs/msg/RouteState.msg new file mode 100644 index 0000000..b3d4ed6 --- /dev/null +++ b/autoware_planning_msgs/msg/RouteState.msg @@ -0,0 +1,11 @@ +uint8 UNKNOWN = 0 +uint8 INITIALIZING = 1 +uint8 UNSET = 2 +uint8 PLANNING = 3 +uint8 SET = 4 +uint8 REROUTING = 5 +uint8 ARRIVED = 6 +uint8 ABORTED = 7 + +builtin_interfaces/Time stamp +uint8 state diff --git a/autoware_planning_msgs/package.xml b/autoware_planning_msgs/package.xml index e0ad5fd..56c623e 100644 --- a/autoware_planning_msgs/package.xml +++ b/autoware_planning_msgs/package.xml @@ -11,9 +11,9 @@ rosidl_default_generators + autoware_common_msgs builtin_interfaces geometry_msgs - nav_msgs std_msgs unique_identifier_msgs diff --git a/autoware_planning_msgs/srv/ClearRoute.srv b/autoware_planning_msgs/srv/ClearRoute.srv new file mode 100644 index 0000000..c6c8fc6 --- /dev/null +++ b/autoware_planning_msgs/srv/ClearRoute.srv @@ -0,0 +1,2 @@ +--- +autoware_common_msgs/ResponseStatus status diff --git a/autoware_planning_msgs/srv/SetLaneletRoute.srv b/autoware_planning_msgs/srv/SetLaneletRoute.srv new file mode 100644 index 0000000..5c456cd --- /dev/null +++ b/autoware_planning_msgs/srv/SetLaneletRoute.srv @@ -0,0 +1,11 @@ +std_msgs/Header header +geometry_msgs/Pose goal_pose +autoware_planning_msgs/LaneletSegment[] segments +unique_identifier_msgs/UUID uuid +bool allow_modification +--- +uint16 ERROR_INVALID_STATE = 1 +uint16 ERROR_PLANNER_UNREADY = 2 +uint16 ERROR_PLANNER_FAILED = 3 +uint16 ERROR_REROUTE_FAILED = 4 +autoware_common_msgs/ResponseStatus status diff --git a/autoware_planning_msgs/srv/SetWaypointRoute.srv b/autoware_planning_msgs/srv/SetWaypointRoute.srv new file mode 100644 index 0000000..23c5b4c --- /dev/null +++ b/autoware_planning_msgs/srv/SetWaypointRoute.srv @@ -0,0 +1,11 @@ +std_msgs/Header header +geometry_msgs/Pose goal_pose +geometry_msgs/Pose[] waypoints +unique_identifier_msgs/UUID uuid +bool allow_modification +--- +uint16 ERROR_INVALID_STATE = 1 +uint16 ERROR_PLANNER_UNREADY = 2 +uint16 ERROR_PLANNER_FAILED = 3 +uint16 ERROR_REROUTE_FAILED = 4 +autoware_common_msgs/ResponseStatus status