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

Message format for RadarTrack #3

Merged
merged 16 commits into from Jan 19, 2021
Merged
Show file tree
Hide file tree
Changes from 11 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
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 eg. 3 = Car)
Copy link
Collaborator

Choose a reason for hiding this comment

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

I generally don't like leaving these open. But definitely don't suggest the usage of 3. This should be expanded to maybe a uint16 and reserve the upper half for additional vendor specific classifications and leave the lower half for potential future standardization.

On the scale of this message optimizing 8 bit vs 16 bit is not worth it.

Copy link
Member

Choose a reason for hiding this comment

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

Agreed. @radarAaron I think the action items here are:

  • change uint8 to uint16 for all pre-defined classifications & classification.
  • Keep car but remove 3 = since that implicitly sets 3 as a car, which I don't think was the intent.

I would suggest we could reserve the first 100 for further standardization rather than 32,000 - that seems excessive. Thoughts?

Choose a reason for hiding this comment

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

I would suggest we could reserve the first 100 for further standardization rather than 32,000 - that seems excessive.

In my experience you end up never having enough of anything. Since you're already going to uint16, really future-proof it and do what @tfoote suggests.

Users won't care whether OEM ids start at 100 or 32000, it's just a number.

Choose a reason for hiding this comment

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

I agree with @gavanderhoorn - Let's start vendor-specific values soemwhere around 32000.

Copy link
Author

Choose a reason for hiding this comment

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

Changes made as requested.

Copy link
Member

Choose a reason for hiding this comment

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

@radarAaron one last part of that - you need to update the uint8's for static, uknown, and dynamic.

Copy link
Author

Choose a reason for hiding this comment

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

done

uint8 NO_CLASSIFICATION=0
uint8 STATIC=1
uint8 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.
uint8 classification # An optional classification of the object (see above)
float64[9] position_covariance # Row-major about the x, y, z axes
Copy link
Collaborator

Choose a reason for hiding this comment

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

This is the current standard for covariance matrices from REP 103 but it is very large.

In the message API review it was deemed that a proposal to cut these down to lower resolution and upper triangular to cut the data size would be valuable: ros2/common_interfaces#91

Would people be interested in trying that out here. It's likely we can cut the covariance data size by two thirds just dropping to 32bit and upper triangular.

In this case it will save 192 of 288 bytes of covariance and will make this message overall about half the size per track. Since the current one has ~288 bytes of covariance and ~104 of position and uuid and one more for the classification.

This would be a good amount of bandwidth savings.

Copy link
Member

@SteveMacenski SteveMacenski Nov 24, 2020

Choose a reason for hiding this comment

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

I'll yield to what you think is best on this front. The only criteria I think is important is consistency, so if other standard interfaces are going to move to this relatively soon, we can do that here first. If its not necessarily sure when that change would be made, I'd rather stick with tried and true.

Choose a reason for hiding this comment

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

Agreed. I'm fine with making this an example of the new standard. Apex.AI made this change internally for similar reasons.

Copy link
Author

Choose a reason for hiding this comment

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

I have updated the covariance fields to float32's. I couldn't find any examples to copy about the wording to use for the upper triangle covariance matrix. Please review and suggest changes if required.

float64[9] velocity_covariance # Row-major about the x, y, z axes
float64[9] acceleration_covariance # Row-major about the x, y, z axes
float64[9] size_covariance # Row-major about the x, y, z axes
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved
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