Skip to content

Commit 30d90b7

Browse files
committed
feat(autoware_planning_msgs): move tier4_planning_msgs to autoware_planning_msgs
Signed-off-by: liu cui <cynthia.liu@autocore.ai>
1 parent 0631905 commit 30d90b7

26 files changed

+178
-0
lines changed

autoware_planning_msgs/CMakeLists.txt

+26
Original file line numberDiff line numberDiff line change
@@ -13,7 +13,33 @@ rosidl_generate_interfaces(${PROJECT_NAME}
1313
"msg/TrajectoryPoint.msg"
1414
"msg/Path.msg"
1515
"msg/PathPoint.msg"
16+
"msg/AvoidanceDebugMsg.msg"
17+
"msg/AvoidanceDebugMsgArray.msg"
18+
"msg/ControlPoint.msg"
19+
"msg/ExpandStopRange.msg"
20+
"msg/LateralOffset.msg"
21+
"msg/PathChangeModule.msg"
22+
"msg/PathChangeModuleId.msg"
23+
"msg/PathPointWithLaneId.msg"
24+
"msg/PathWithLaneId.msg"
25+
"msg/PlanningFactor.msg"
26+
"msg/PlanningFactorArray.msg"
27+
"msg/RerouteAvailability.msg"
28+
"msg/RouteState.msg"
29+
"msg/SafetyFactor.msg"
30+
"msg/SafetyFactorArray.msg"
31+
"msg/Scenario.msg"
32+
"msg/StopFactor.msg"
33+
"msg/StopSpeedExceeded.msg"
34+
"msg/VelocityLimit.msg"
35+
"msg/VelocityLimitClearCommand.msg"
36+
"msg/VelocityLimitConstraints.msg"
37+
"srv/ClearRoute.srv"
38+
"srv/SetLaneletRoute.srv"
39+
"srv/SetWaypointRoute.srv"
1640
DEPENDENCIES
41+
autoware_common_msgs
42+
autoware_perception_msgs
1743
geometry_msgs
1844
std_msgs
1945
unique_identifier_msgs
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,9 @@
1+
string object_id
2+
bool allow_avoidance
3+
float64 longitudinal_distance
4+
float64 lateral_distance_from_centerline
5+
float64 to_furthest_linestring_distance
6+
float64 max_shift_length
7+
float64 required_jerk
8+
float64 maximum_jerk
9+
string failed_reason
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,2 @@
1+
std_msgs/Header header
2+
autoware_planning_msgs/AvoidanceDebugMsg[] avoidance_info
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,4 @@
1+
geometry_msgs/Pose pose
2+
float32 velocity
3+
float32 shift_length
4+
float32 distance
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,2 @@
1+
builtin_interfaces/Time stamp
2+
float32 expand_stop_range
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,2 @@
1+
builtin_interfaces/Time stamp
2+
float32 lateral_offset
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,2 @@
1+
std_msgs/Header header
2+
autoware_planning_msgs/PathChangeModuleId module
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,8 @@
1+
int32 type
2+
3+
int32 NONE = 0
4+
int32 AVOIDANCE = 1
5+
int32 LANE_CHANGE = 2
6+
int32 FORCE_LANE_CHANGE = 3
7+
int32 GOAL_PLANNER = 4
8+
int32 START_PLANNER = 5
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,2 @@
1+
autoware_planning_msgs/PathPoint point
2+
int64[] lane_ids
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,4 @@
1+
std_msgs/Header header
2+
autoware_planning_msgs/PathPointWithLaneId[] points
3+
geometry_msgs/Point[] left_bound
4+
geometry_msgs/Point[] right_bound
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,20 @@
1+
# constants for behavior
2+
uint16 UNKNOWN = 0
3+
uint16 NONE = 1
4+
uint16 SLOW_DOWN = 2
5+
uint16 STOP = 3
6+
uint16 LEFT_SHIFT = 4
7+
uint16 RIGHT_SHIFT = 5
8+
9+
# variables
10+
string module
11+
12+
bool is_driving_forward
13+
14+
autoware_planning_msgs/ControlPoint[] control_points
15+
16+
uint16 behavior
17+
18+
string detail
19+
20+
autoware_planning_msgs/SafetyFactorArray safety_factors
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,2 @@
1+
std_msgs/Header header
2+
autoware_planning_msgs/PlanningFactor[] factors
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,2 @@
1+
builtin_interfaces/Time stamp
2+
bool availability
+12
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,12 @@
1+
uint8 UNKNOWN = 0
2+
uint8 INITIALIZING = 1
3+
uint8 UNSET = 2
4+
uint8 ROUTING = 3
5+
uint8 SET = 4
6+
uint8 REROUTING = 5
7+
uint8 ARRIVED = 6
8+
uint8 ABORTED = 7
9+
uint8 INTERRUPTED = 8
10+
11+
builtin_interfaces/Time stamp
12+
uint8 state
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,27 @@
1+
# constants for common use
2+
uint16 UNKNOWN = 0
3+
4+
# constants for factor type
5+
uint16 POINTCLOUD = 1
6+
uint16 OBJECT = 2
7+
8+
# variables
9+
uint16 type
10+
11+
# use only for predicted objects
12+
unique_identifier_msgs/UUID object_id
13+
14+
# use only for predicted objects
15+
autoware_perception_msgs/PredictedPath predicted_path
16+
17+
# time to collision in relative to the header time
18+
float32 ttc_begin
19+
20+
float32 ttc_end
21+
22+
# type == POINTCLOUD: the position of the each points
23+
# type == OBJECT: the object position
24+
geometry_msgs/Point[] points
25+
26+
# module's primitive judgement of the safety for its decision
27+
bool is_safe
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,4 @@
1+
std_msgs/Header header
2+
autoware_planning_msgs/SafetyFactor[] factors
3+
bool is_safe
4+
string detail
+6
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,6 @@
1+
string EMPTY=Empty
2+
string LANEDRIVING=LaneDriving
3+
string PARKING=Parking
4+
5+
string current_scenario
6+
string[] activating_scenarios
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,3 @@
1+
geometry_msgs/Pose stop_pose
2+
float64 dist_to_stop_pose
3+
geometry_msgs/Point[] stop_factor_points
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,2 @@
1+
builtin_interfaces/Time stamp
2+
bool stop_speed_exceeded
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,7 @@
1+
builtin_interfaces/Time stamp
2+
float32 max_velocity
3+
4+
bool use_constraints false
5+
autoware_planning_msgs/VelocityLimitConstraints constraints
6+
7+
string sender
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,3 @@
1+
builtin_interfaces/Time stamp
2+
bool command false
3+
string sender
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,11 @@
1+
# maximum signed acceleration
2+
float32 max_acceleration
3+
4+
# minimum signed acceleration
5+
float32 min_acceleration
6+
7+
# maximum signed jerk
8+
float32 max_jerk
9+
10+
# minimum signed jerk
11+
float32 min_jerk

autoware_planning_msgs/package.xml

+2
Original file line numberDiff line numberDiff line change
@@ -12,6 +12,8 @@
1212

1313
<build_depend>rosidl_default_generators</build_depend>
1414

15+
<depend>autoware_common_msgs</depend>
16+
<depend>autoware_perception_msgs</depend>
1517
<depend>builtin_interfaces</depend>
1618
<depend>geometry_msgs</depend>
1719
<depend>nav_msgs</depend>
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,2 @@
1+
---
2+
autoware_common_msgs/ResponseStatus status
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,7 @@
1+
std_msgs/Header header
2+
geometry_msgs/Pose goal_pose
3+
autoware_planning_msgs/LaneletSegment[] segments
4+
unique_identifier_msgs/UUID uuid
5+
bool allow_modification
6+
---
7+
autoware_common_msgs/ResponseStatus status
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,7 @@
1+
std_msgs/Header header
2+
geometry_msgs/Pose goal_pose
3+
geometry_msgs/Pose[] waypoints
4+
unique_identifier_msgs/UUID uuid
5+
bool allow_modification
6+
---
7+
autoware_common_msgs/ResponseStatus status

0 commit comments

Comments
 (0)