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_internal_planning_msgs): adaption to autoware_motion_utils #45

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
7 changes: 7 additions & 0 deletions autoware_internal_planning_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -18,10 +18,17 @@ rosidl_generate_interfaces(${PROJECT_NAME}
"msg/PathPointWithLaneId.msg"
"msg/PathWithLaneId.msg"
"msg/Scenario.msg"
"msg/ControlPoint.msg"
"msg/SafetyFactor.msg"
"msg/SafetyFactorArray.msg"
"msg/PlanningFactor.msg"
"msg/PlanningFactorArray.msg"
DEPENDENCIES
builtin_interfaces
geometry_msgs
std_msgs
unique_identifier_msgs
autoware_perception_msgs
autoware_planning_msgs
)

Expand Down
4 changes: 4 additions & 0 deletions autoware_internal_planning_msgs/msg/ControlPoint.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
geometry_msgs/Pose pose
float32 velocity
float32 shift_length
float32 distance
22 changes: 22 additions & 0 deletions autoware_internal_planning_msgs/msg/PlanningFactor.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,22 @@
# constants for behavior
uint16 UNKNOWN = 0
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

# variables
string module

bool is_driving_forward

autoware_internal_planning_msgs/ControlPoint[] control_points

uint16 behavior

string detail

autoware_internal_planning_msgs/SafetyFactorArray safety_factors
2 changes: 2 additions & 0 deletions autoware_internal_planning_msgs/msg/PlanningFactorArray.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
std_msgs/Header header
autoware_internal_planning_msgs/PlanningFactor[] factors
27 changes: 27 additions & 0 deletions autoware_internal_planning_msgs/msg/SafetyFactor.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@
# constants for common use
uint16 UNKNOWN = 0

# constants for factor type
uint16 POINTCLOUD = 1
uint16 OBJECT = 2

# variables
uint16 type

# use only for predicted objects
unique_identifier_msgs/UUID object_id

# use only for predicted objects
autoware_perception_msgs/PredictedPath predicted_path

# time to collision in relative to the header time
float32 ttc_begin

float32 ttc_end

# type == POINTCLOUD: the position of the each points
# type == OBJECT: the object position
geometry_msgs/Point[] points

# module's primitive judgement of the safety for its decision
bool is_safe
4 changes: 4 additions & 0 deletions autoware_internal_planning_msgs/msg/SafetyFactorArray.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
std_msgs/Header header
autoware_internal_planning_msgs/SafetyFactor[] factors
bool is_safe
string detail
2 changes: 2 additions & 0 deletions autoware_internal_planning_msgs/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -13,10 +13,12 @@

<exec_depend>rosidl_default_runtime</exec_depend>

<depend>autoware_perception_msgs</depend>
<depend>autoware_planning_msgs</depend>
<depend>builtin_interfaces</depend>
<depend>geometry_msgs</depend>
<depend>std_msgs</depend>
<depend>unique_identifier_msgs</depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
Expand Down