Skip to content

Commit

Permalink
Message format for RadarTrack (#3)
Browse files Browse the repository at this point in the history
* Added message format for RadarTrack

* Spelling correction

* Altered classification to uint8

* Changed track_id to UUID and updated the description of 'size'

* Updated description of size to allow for better compatiablity of rectangle-shaped bounding boxes.

* Added covariance matrix

* Adjusted covariance format

* Altered notes for classification and size fields as per feedback on the pull request

* Making the size frame of reference explicit

* Added comment about that this message relating only to FMCW radar

* Added constants for object classification field

* Added new line to the end of the file

* Altered description and data type of classification and changed the covariance fields

* Updated types for object classification enums

* Added dependencies to CMakelists.txt and package.xml

Co-authored-by: AARON-FULTONZ\Aaron <[email protected]>
  • Loading branch information
radarAaron and aaronfultonnz authored Jan 19, 2021
1 parent d02637a commit 3c578b0
Show file tree
Hide file tree
Showing 4 changed files with 31 additions and 1 deletion.
4 changes: 3 additions & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,9 @@ find_package(std_msgs REQUIRED)
rosidl_generate_interfaces(${PROJECT_NAME}
"msg/RadarReturn.msg"
"msg/RadarScan.msg"
DEPENDENCIES builtin_interfaces std_msgs
"msg/RadarTrack.msg"
"msg/RadarTracks.msg"
DEPENDENCIES builtin_interfaces std_msgs uuid_msgs geometry_msgs
)

ament_export_dependencies(rosidl_default_runtime)
Expand Down
23 changes: 23 additions & 0 deletions msg/RadarTrack.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
# 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
3 changes: 3 additions & 0 deletions msg/RadarTracks.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
std_msgs/Header header

radar_msgs/RadarTracks[] tracks
2 changes: 2 additions & 0 deletions package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,8 @@
<buildtool_depend>ament_cmake</buildtool_depend>

<depend>std_msgs</depend>
<depend>uuid_msgs</depend>
<depend>geometry_msgs</depend>
<depend>rosidl_default_generators</depend>
<depend>builtin_interfaces</depend>

Expand Down

0 comments on commit 3c578b0

Please sign in to comment.