diff --git a/autoware_internal_debug_msgs/CMakeLists.txt b/autoware_internal_debug_msgs/CMakeLists.txt index 74a8a3b..9739610 100644 --- a/autoware_internal_debug_msgs/CMakeLists.txt +++ b/autoware_internal_debug_msgs/CMakeLists.txt @@ -15,6 +15,8 @@ set(msg_files "msg/Int64Stamped.msg" "msg/Int64MultiArrayStamped.msg" "msg/StringStamped.msg" + "msg/ProcessingTimeNode.msg" + "msg/ProcessingTimeTree.msg" ) set(srv_files diff --git a/autoware_internal_debug_msgs/msg/ProcessingTimeNode.msg b/autoware_internal_debug_msgs/msg/ProcessingTimeNode.msg new file mode 100644 index 0000000..e7d4409 --- /dev/null +++ b/autoware_internal_debug_msgs/msg/ProcessingTimeNode.msg @@ -0,0 +1,10 @@ +# Unique ID of the node +int32 id +# Name of the node +string name +# Processing time of the node +float64 processing_time +# ID of the parent node, 0 if no parent +int32 parent_id +# Comment +string comment diff --git a/autoware_internal_debug_msgs/msg/ProcessingTimeTree.msg b/autoware_internal_debug_msgs/msg/ProcessingTimeTree.msg new file mode 100644 index 0000000..0e7be75 --- /dev/null +++ b/autoware_internal_debug_msgs/msg/ProcessingTimeTree.msg @@ -0,0 +1,2 @@ +# Array of all time nodes +ProcessingTimeNode[] nodes diff --git a/autoware_internal_planning_msgs/CMakeLists.txt b/autoware_internal_planning_msgs/CMakeLists.txt index 5dc7a71..7fe90aa 100644 --- a/autoware_internal_planning_msgs/CMakeLists.txt +++ b/autoware_internal_planning_msgs/CMakeLists.txt @@ -15,6 +15,9 @@ find_package(ament_cmake_auto REQUIRED) ament_auto_find_build_dependencies() rosidl_generate_interfaces(${PROJECT_NAME} + "msg/PathPoint.msg" + "msg/PathPointWithLaneId.msg" + "msg/PathWithLaneId.msg" "msg/Scenario.msg" DEPENDENCIES builtin_interfaces diff --git a/autoware_internal_planning_msgs/msg/PathPoint.msg b/autoware_internal_planning_msgs/msg/PathPoint.msg new file mode 100644 index 0000000..697681f --- /dev/null +++ b/autoware_internal_planning_msgs/msg/PathPoint.msg @@ -0,0 +1,5 @@ +geometry_msgs/Pose pose +float32 longitudinal_velocity_mps +float32 lateral_velocity_mps +float32 heading_rate_rps +bool is_final diff --git a/autoware_internal_planning_msgs/msg/PathPointWithLaneId.msg b/autoware_internal_planning_msgs/msg/PathPointWithLaneId.msg new file mode 100644 index 0000000..25a02d2 --- /dev/null +++ b/autoware_internal_planning_msgs/msg/PathPointWithLaneId.msg @@ -0,0 +1,2 @@ +autoware_internal_planning_msgs/PathPoint point +int64[] lane_ids diff --git a/autoware_internal_planning_msgs/msg/PathWithLaneId.msg b/autoware_internal_planning_msgs/msg/PathWithLaneId.msg new file mode 100644 index 0000000..27a74bc --- /dev/null +++ b/autoware_internal_planning_msgs/msg/PathWithLaneId.msg @@ -0,0 +1,4 @@ +std_msgs/Header header +autoware_internal_planning_msgs/PathPointWithLaneId[] points +geometry_msgs/Point[] left_bound +geometry_msgs/Point[] right_bound