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_perception_msgs): implement the proposed universal radar messages #120

Open
wants to merge 8 commits into
base: main
Choose a base branch
from
4 changes: 4 additions & 0 deletions autoware_perception_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,10 @@ rosidl_generate_interfaces(${PROJECT_NAME}
"msg/PredictedObjectKinematics.msg"
"msg/PredictedObjects.msg"
"msg/PredictedPath.msg"
"msg/RadarFieldInfo.msg"
"msg/RadarInfo.msg"
"msg/RadarObject.msg"
"msg/RadarObjects.msg"
"msg/Shape.msg"
"msg/TrackedObject.msg"
"msg/TrackedObjectKinematics.msg"
Expand Down
4 changes: 4 additions & 0 deletions autoware_perception_msgs/msg/ObjectClassification.msg
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,10 @@ uint8 TRAILER = 4
uint8 MOTORCYCLE = 5
uint8 BICYCLE = 6
uint8 PEDESTRIAN = 7
uint8 ANIMAL = 8
uint8 HAZARD = 9
uint8 OVER_DRIVABLE = 10
uint8 UNDER_DRIVABLE = 11

uint8 label
float32 probability
8 changes: 8 additions & 0 deletions autoware_perception_msgs/msg/RadarFieldInfo.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
std_msgs/String field_name
bool min_value_available
bool max_value_available
bool resolution_available

float32 min_value
float32 max_value
float32 resolution
6 changes: 6 additions & 0 deletions autoware_perception_msgs/msg/RadarInfo.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
std_msgs/Header header
RadarFieldInfo[] object_fields_info
RadarFieldInfo[] detection_fields_info

uint32[] available_classes
bool absolute_dynamics # absolute or relative dynamics
35 changes: 35 additions & 0 deletions autoware_perception_msgs/msg/RadarObject.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,35 @@
float32 INVALID_COV_VALUE = -1.0

uint8 MEASUREMENT_STATUS_INVALID = 0
uint8 MEASUREMENT_STATUS_MEASURED = 1
uint8 MEASUREMENT_STATUS_PREDICTED = 2
uint8 MEASUREMENT_STATUS_NEW = 3
uint8 MEASUREMENT_STATUS_UNKNOWN = 4

uint8 MOVEMENT_STATUS_INVALID = 0
uint8 MOVEMENT_STATUS_DYNAMIC = 1
uint8 MOVEMENT_STATUS_STATIC = 2
uint8 MOVEMENT_STATUS_UNKNOWN = 3

uint32 object_id
uint16 age
uint8 measurement_status
uint8 movement_status

geometry_msgs/Point position
geometry_msgs/Vector3 velocity
geometry_msgs/Vector3 acceleration
geometry_msgs/Vector3 size

float32[6] position_covariance
float32[6] velocity_covariance
float32[6] acceleration_covariance
float32[6] size_covariance

float32 orientation
float32 orientation_std
float32 orientation_rate
float32 orientation_rate_std

float32 existence_probability
ObjectClassification[] classifications
2 changes: 2 additions & 0 deletions autoware_perception_msgs/msg/RadarObjects.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
std_msgs/Header header
RadarObject[] objects
3 changes: 2 additions & 1 deletion autoware_sensing_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,8 @@ ament_auto_find_build_dependencies()

set(msg_files
"msg/GnssInsOrientation.msg"
"msg/GnssInsOrientationStamped.msg")
"msg/GnssInsOrientationStamped.msg"
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Could you put the parenthesis back up? To keep consistent.

)

set(msg_dependencies
geometry_msgs
Expand Down