Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat(autoware_adapi_v1_msgs): add cooperation #41

Merged
merged 16 commits into from
Sep 4, 2023
Merged
11 changes: 10 additions & 1 deletion autoware_adapi_v1_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,15 @@ rosidl_generate_interfaces(${PROJECT_NAME}
planning/msg/SteeringFactorArray.msg
planning/msg/VelocityFactor.msg
planning/msg/VelocityFactorArray.msg
planning/msg/PlanningBehavior.msg
planning/msg/PlanningSequence.msg
planning/msg/CooperationCommand.msg
planning/msg/CooperationDecision.msg
planning/msg/CooperationPolicy.msg
planning/msg/CooperationStatus.msg
planning/srv/SetCooperationCommands.srv
planning/srv/SetCooperationPolicies.srv
planning/srv/GetCooperationPolicies.srv
system/msg/MrmState.msg
vehicle/msg/DoorLayout.msg
vehicle/msg/DoorStatus.msg
Expand All @@ -44,10 +53,10 @@ rosidl_generate_interfaces(${PROJECT_NAME}
vehicle/srv/GetVehicleDimensions.srv
DEPENDENCIES
builtin_interfaces
std_msgs
geographic_msgs
geometry_msgs
shape_msgs
std_msgs
unique_identifier_msgs
)

Expand Down
2 changes: 2 additions & 0 deletions autoware_adapi_v1_msgs/planning/msg/CooperationCommand.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
unique_identifier_msgs/UUID uuid
autoware_adapi_v1_msgs/CooperationDecision cooperator
7 changes: 7 additions & 0 deletions autoware_adapi_v1_msgs/planning/msg/CooperationDecision.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
uint8 UNKNOWN = 0
uint8 DEACTIVATE = 1
uint8 ACTIVATE = 2
uint8 AUTONOMOUS = 3
uint8 UNDECIDED = 4

uint8 decision
6 changes: 6 additions & 0 deletions autoware_adapi_v1_msgs/planning/msg/CooperationPolicy.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
uint8 OPTIONAL = 1
uint8 REQUIRED = 2

string behavior
string sequence
uint8 policy
4 changes: 4 additions & 0 deletions autoware_adapi_v1_msgs/planning/msg/CooperationStatus.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
unique_identifier_msgs/UUID uuid
autoware_adapi_v1_msgs/CooperationDecision autonomous
autoware_adapi_v1_msgs/CooperationDecision cooperator
bool cancellable
16 changes: 16 additions & 0 deletions autoware_adapi_v1_msgs/planning/msg/PlanningBehavior.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
# These constants are used in the behavior field of the SteeringFactor/VelocityFactor.
string AVOIDANCE = "avoidance"
string CROSSWALK = "crosswalk"
string EMERGENCY_OPERATION = "emergency-operation"
string INTERSECTION = "intersection"
string LANE_CHANGE = "lane-change"
string MERGE = "merge"
string NO_DRIVABLE_LANE = "no-drivable-lane"
string NO_STOPPING_AREA = "no-stopping-area"
string REAR_CHECK = "rear-check"
string ROUTE_OBSTACLE = "route-obstacle"
string SIDEWALK = "sidewalk"
string STOP_SIGN = "stop-sign"
string SURROUNDING_OBSTACLE = "surrounding-obstacle"
string TRAFFIC_SIGNAL = "traffic-signal"
string USER_DEFINED_DETECTION_AREA = "user-defined-attention-area"
5 changes: 5 additions & 0 deletions autoware_adapi_v1_msgs/planning/msg/PlanningSequence.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
# These constants are used in the sequence field of the SteeringFactor/VelocityFactor.

# for avoidance behavior
string CHANGE = "change"
string RETURN = "return"
37 changes: 23 additions & 14 deletions autoware_adapi_v1_msgs/planning/msg/SteeringFactor.msg
Original file line number Diff line number Diff line change
@@ -1,32 +1,41 @@
# constants for common use
uint16 UNKNOWN = 0

# constants for type
uint16 INTERSECTION = 1
uint16 LANE_CHANGE = 2
uint16 AVOIDANCE_PATH_CHANGE = 3
uint16 AVOIDANCE_PATH_RETURN = 4
uint16 STATION = 5
uint16 PULL_OUT = 6 # Deprecated. Use START_PLANNER.
uint16 START_PLANNER = 6
uint16 PULL_OVER = 7 # Deprecated. Use GOAL_PLANNER.
uint16 GOAL_PLANNER = 7
uint16 EMERGENCY_OPERATION = 8

# constants for direction
uint16 LEFT = 1
uint16 RIGHT = 2
uint16 STRAIGHT = 3

# constants for status
uint16 APPROACHING = 1
uint16 TRYING = 2
uint16 TURNING = 3

# variables
geometry_msgs/Pose[2] pose
float32[2] distance
uint16 type
uint16 direction
uint16 status
string behavior
string sequence
string detail
autoware_adapi_v1_msgs/CooperationStatus[<=1] cooperation



# deprecated constants for type
mitsudome-r marked this conversation as resolved.
Show resolved Hide resolved
uint16 INTERSECTION = 1
uint16 LANE_CHANGE = 2
uint16 AVOIDANCE_PATH_CHANGE = 3
uint16 AVOIDANCE_PATH_RETURN = 4
uint16 STATION = 5
uint16 PULL_OUT = 6 # Deprecated. Use START_PLANNER.
uint16 START_PLANNER = 6
uint16 PULL_OVER = 7 # Deprecated. Use GOAL_PLANNER.
uint16 GOAL_PLANNER = 7
uint16 EMERGENCY_OPERATION = 8

# deprecated constants for status
uint16 TRYING = 2

# deprecated variables
uint16 type
27 changes: 17 additions & 10 deletions autoware_adapi_v1_msgs/planning/msg/VelocityFactor.msg
Original file line number Diff line number Diff line change
@@ -1,7 +1,22 @@
# constants for common use
uint16 UNKNOWN = 0

# constants for type
# constants for status
uint16 APPROACHING = 1
uint16 STOPPED = 2

# variables
geometry_msgs/Pose pose
float32 distance
uint16 status
string behavior
string sequence
string detail
autoware_adapi_v1_msgs/CooperationStatus[<=1] cooperation



# deprecated constants for type
uint16 SURROUNDING_OBSTACLE = 1
uint16 ROUTE_OBSTACLE = 2
uint16 INTERSECTION = 3
Expand All @@ -20,13 +35,5 @@ uint16 AVOIDANCE = 15
uint16 EMERGENCY_STOP_OPERATION = 16
uint16 NO_DRIVABLE_LANE = 17

# constants for status
uint16 APPROACHING = 1
uint16 STOPPED = 2

# variables
geometry_msgs/Pose pose
float32 distance
# deprecated variables
uint16 type
uint16 status
string detail
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
---
autoware_adapi_v1_msgs/ResponseStatus status
autoware_adapi_v1_msgs/CooperationPolicy[] policies
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
autoware_adapi_v1_msgs/CooperationCommand[] commands
---
autoware_adapi_v1_msgs/ResponseStatus status
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
autoware_adapi_v1_msgs/CooperationPolicy[] policies
---
autoware_adapi_v1_msgs/ResponseStatus status