diff --git a/autoware_adapi_v1_msgs/CMakeLists.txt b/autoware_adapi_v1_msgs/CMakeLists.txt index bdef13a..3aa025e 100644 --- a/autoware_adapi_v1_msgs/CMakeLists.txt +++ b/autoware_adapi_v1_msgs/CMakeLists.txt @@ -38,11 +38,14 @@ rosidl_generate_interfaces(${PROJECT_NAME} perception/msg/DynamicObjectKinematics.msg perception/msg/DynamicObjectPath.msg perception/msg/ObjectClassification.msg + planning/msg/ControlPoint.msg planning/msg/SteeringFactor.msg planning/msg/SteeringFactorArray.msg planning/msg/VelocityFactor.msg planning/msg/VelocityFactorArray.msg planning/msg/PlanningBehavior.msg + planning/msg/PlanningFactor.msg + planning/msg/PlanningFactorArray.msg planning/msg/PlanningSequence.msg planning/msg/CooperationCommand.msg planning/msg/CooperationDecision.msg diff --git a/autoware_adapi_v1_msgs/planning/msg/ControlPoint.msg b/autoware_adapi_v1_msgs/planning/msg/ControlPoint.msg new file mode 100644 index 0000000..5c71444 --- /dev/null +++ b/autoware_adapi_v1_msgs/planning/msg/ControlPoint.msg @@ -0,0 +1,2 @@ +geometry_msgs/Pose pose +float32 distance diff --git a/autoware_adapi_v1_msgs/planning/msg/PlanningFactor.msg b/autoware_adapi_v1_msgs/planning/msg/PlanningFactor.msg new file mode 100644 index 0000000..45c4eda --- /dev/null +++ b/autoware_adapi_v1_msgs/planning/msg/PlanningFactor.msg @@ -0,0 +1,38 @@ +## constants for common use +uint16 UNKNOWN = 0 + +# constants for behavior_type +uint16 NONE = 1 +uint16 SLOW_DOWN = 2 +uint16 STOP = 3 +uint16 SHIFT_LEFT = 4 +uint16 SHIFT_RIGHT = 5 +uint16 TURN_LEFT = 6 +uint16 TURN_RIGHT = 7 + +# constants for behavior_name +string ADAPTIVE_CRUISE = "adaptive_cruise" +string AVOIDANCE = "avoidance" +string CROSSWALK = "crosswalk" +string GOAL_PLANNER = "goal_planner" +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 RUN_OUT = "run_out" +string SIDEWALK = "sidewalk" +string START_PLANNER = "start_planner" +string STOP_SIGN = "stop_sign" +string SURROUNDING_OBSTACLE = "surrounding_obstacle" +string TRAFFIC_SIGNAL = "traffic_signal" +string USER_DEFINED_DETECTION_AREA = "user_defined_detection_area" +string VIRTUAL_TRAFFIC_LIGHT = "virtual_traffic_light" + +# variables +uint16 behavior_type +string behavior_name +string detail +autoware_adapi_v1_msgs/ControlPoint[] control_points diff --git a/autoware_adapi_v1_msgs/planning/msg/PlanningFactorArray.msg b/autoware_adapi_v1_msgs/planning/msg/PlanningFactorArray.msg new file mode 100644 index 0000000..4f1c9e3 --- /dev/null +++ b/autoware_adapi_v1_msgs/planning/msg/PlanningFactorArray.msg @@ -0,0 +1,2 @@ +std_msgs/Header header +autoware_adapi_v1_msgs/PlanningFactor[] factors