radar_msgs/RadarTrack Message

File: radar_msgs/RadarTrack.msg

Raw Message Definition

# This message relates only to FMCW radar.  
# All variables below are relative to the radar's frame of reference.
# This message is not meant to be used alone but as part of a stamped or array message.

# Object classifications (Additional vendor-specific classifications are permitted starting from 32000 eg. Car)
uint16 NO_CLASSIFICATION=0
uint16 STATIC=1
uint16 DYNAMIC=2


uuid_msgs/UniqueID uuid                     # A unique ID of the object generated by the radar.

                                            # Note: The z component of these fields is ignored for 2D tracking.
geometry_msgs/Point position                # x, y, z coordinates of the centroid of the object being tracked.
geometry_msgs/Vector3 velocity              # The velocity of the object in each spatial dimension.
geometry_msgs/Vector3 acceleration          # The acceleration of the object in each spatial dimension.
geometry_msgs/Vector3 size                  # The object size as represented by the radar sensor eg. length, width, height OR the diameter of an ellipsoid in the x, y, z, dimensions
                                            # and is from the sensor frame's view.
uint16 classification                       # An optional classification of the object (see above)
float32[6] position_covariance              # Upper-triangle covariance about the x, y, z axes
float32[6] velocity_covariance              # Upper-triangle covariance about the x, y, z axes
float32[6] acceleration_covariance          # Upper-triangle covariance about the x, y, z axes
float32[6] size_covariance                  # Upper-triangle covariance about the x, y, z axes

Compact Message Definition

uint16 NO_CLASSIFICATION=0
uint16 STATIC=1
uint16 DYNAMIC=2
uuid_msgs/UniqueID uuid
geometry_msgs/Point position
geometry_msgs/Vector3 velocity
geometry_msgs/Vector3 acceleration
geometry_msgs/Vector3 size
uint16 classification
float32[6] position_covariance
float32[6] velocity_covariance
float32[6] acceleration_covariance
float32[6] size_covariance