autoware-documentation
autoware-documentation copied to clipboard
docs(sensing): add sensing design documentation
Signed-off-by: M. Fatih Cırıt [email protected]
Description
This PR adds documentation for sensing part of the autoware modules.
I've separated the design docs by data types.
Pre-review checklist for the PR author
The PR author must check the checkboxes below when creating the PR.
- [x] I've confirmed the contribution guidelines.
- [x] The PR follows the pull request guidelines.
In-review checklist for the PR reviewers
The Reviewers must check the checkboxes below before approval.
- [ ] The PR follows the pull request guidelines.
Post-review checklist for the PR author
The PR author must check the checkboxes below before merging.
- [ ] There are no open discussions or they are tracked via tickets.
After all checkboxes are checked, anyone who has write access can merge the PR.
Documentation URL: https://autowarefoundation.github.io/autoware-documentation/pr-180/ Modified URLs:
- https://autowarefoundation.github.io/autoware-documentation/pr-180/design/autoware-architecture/sensing/data-types/gnss-ins-data/
- https://autowarefoundation.github.io/autoware-documentation/pr-180/design/autoware-architecture/sensing/data-types/image/
- https://autowarefoundation.github.io/autoware-documentation/pr-180/design/autoware-architecture/sensing/data-types/point-cloud/
- https://autowarefoundation.github.io/autoware-documentation/pr-180/design/autoware-architecture/sensing/data-types/radar-data/
- https://autowarefoundation.github.io/autoware-documentation/pr-180/design/autoware-architecture/sensing/data-types/ultrasonics-data/
- https://autowarefoundation.github.io/autoware-documentation/pr-180/design/autoware-architecture/sensing/
I've prepared the
- https://autowarefoundation.github.io/autoware-documentation/pr-180/design/autoware-architecture/sensing/
- https://autowarefoundation.github.io/autoware-documentation/pr-180/design/autoware-architecture/sensing/data-types/point-cloud/
pages for this PR and added the templates for the other sensor pipelines.
@yukkysaito could you please review?
@xmfcx Thank you! Sure :+1:
@yukkysaito thanks for your review. Can you review it again? I've applied your suggestions and rebased it to main branch.
@xmfcx LGTM :+1: Just in case, @miursh @drwnz can you review this?
@miursh @drwnz can you review this?
@xmfcx Thank you for writing this great document! Because I'm not familiar with what point type is used in Bus ODD, I might say some wrong stuff. But actually, the point type written here is different from what we T4 uses in autoware.universe. As @aohsato said here, we currently use a PointXYZIRADRT (which stands for XYZ, Intensity, Ring, Azimuth, Distance, Return_type and Time_stamp) and return type definition for some sensing modules.
Are we supposed to resolve this conflict? @aohsato @drwnz How should we write such differences in this document? @xmfcx @mitsudome-r
@xmfcx But actually, the point type written here is different from what we T4 uses in autoware.universe. As @aohsato said here, we currently use a PointXYZIRADRT (which stands for XYZ, Intensity, Ring, Azimuth, Distance, Return_type and Time_stamp) and return type definition for some sensing modules.
My opinions on PointXYZIRADRT
@miursh I am aware of the PointXYZIRADRT type. Problem with this type is, A(azimuth) and D(distance) fields are redundant.
Intensity
Using float for intensity is waste of bit space since lidars output it as a single byte.
Ring
I also represented it with a uint16_t but with "laser_channel" name to be able to represent solid state lidars too.
Azimuth
Azimuth of a point can be calculated with std::atan2:
az = std::atan2(p.y, p.x)
Distance
Distance of a point can be calculated with std::hypot:
dist = std::hypot(p.x, p.y, p.z)
Return type
In velodyne, return type of a point can only be strongest or last return. Whether lidar is in Strongest Return, Last Return or Dual Return mode.
This is why I only added 3 fields https://github.com/autowarefoundation/autoware-documentation/blob/5e8be02558ae561ee18b3c7b5f1b89becf4ffd38/docs/design/autoware-architecture/sensing/data-types/point-cloud.md#return-type
I am open to add following
enum ReturnType : uint8_t {
INVALID = 0,
SINGLE_STRONGEST,
SINGLE_LAST,
DUAL_STRONGEST_FIRST,
DUAL_STRONGEST_LAST,
DUAL_WEAK_FIRST,
DUAL_WEAK_LAST,
DUAL_ONLY,
};
types to the list too, if you help me understand why they are necessary, also your lidar datasheet would help too.
Time stamp
I've explained why I chose to represent it with a uint32_t in https://github.com/autowarefoundation/autoware-documentation/blob/5e8be02558ae561ee18b3c7b5f1b89becf4ffd38/docs/design/autoware-architecture/sensing/data-types/point-cloud.md#time
For summary, it is more compact and more precise nanoseconds count (compared to floating point representations).
Are we suppose to resolve this conflict? @aohsato @drwnz How should we write such differences in this document? @xmfcx @mitsudome-r
This is why I'm asking for your review. Once we finalize the core type definitions and standardize them, we can start refactoring the Universe codebase too.
Right now I think the PointXYZIRC is very compact with 16 bytes, equal to previous PointXYZI. With the time field only at the top of the stack PointXYZIRCT being 24 bytes.
I'm open to suggestions/improvements on the point type definitions.
@xmfcx I'm fine with your opinion about Intensity/laser_Channel/Time stamp. I'm not sure about this line below can be applied to all LiDAR sensors though.
Using float for intensity is waste of bit space since lidars output it as a single byte.
Azimuth/Distance
For Azimuth and Distance, I don't want calculate those for each point since we might handle more than 200,000 points if LiDAR like VLS128 is used. It requires too much extra computational cost. On contrast, drivers do not have to calculate them because drivers likely know the exact value for distance and azimuth.
Return type
For Return type, drivers are only nodes that can calculate strongest_last, weak_first, or other return type for dual return mode of one single laser. Since some LiDAR diagnostic node use the return type, that should be included in the point member.
We are thinking we can categorize points to image below based on the return mode, distance and intensity,

@aohsato @drwnz @badai-nguyen If you have any thoughts, please let us know.
@miursh
I'm not sure about this line below can be applied to all LiDAR sensors though.
Using float for intensity is waste of bit space since lidars output it as a single byte.
https://autowarefoundation.github.io/autoware-documentation/pr-180/design/autoware-architecture/sensing/data-types/point-cloud/#intensity-mapping-for-other-lidar-brands here I've gone through the manuals of 5 non-velodyne lidar brands for this, if you know a lidar that uses more bytes to represent it, please let me know.
Azimuth/Distance For Azimuth and Distance, I don't want calculate those for each point since we might handle more than 200,000 points if LiDAR like VLS128 is used. It requires too much extra computational cost. On contrast, drivers do not have to calculate them because drivers likely know the exact value for distance and azimuth.
I am aware of the computational cost but I thought it would be negligible. I've made a simple benchmark, it takes about 3ms to recalculate distance and azimuth of 200 000 points (not negligible). So I will reconsider the point fields to include these in an acceptable way.
@miursh You can check the benchmark here: https://github.com/xmfcx/bench_point_cloud#readme
@xmfcx Thanks for your great documentation and interesting benchmarks! As your benchmarks show, recalculating Azimuth/Distance is computationally expensive, so we'd like to be able to add them to the data field. However, there may be situations where memory resources are not enough, so it may be better to handle it as an optional field.
NOTE: That's why we use azimuth/distance field, but the pointcloud wrapper merging seem to make those custom fields unavailable currently as @miursh mentioned. https://github.com/autowarefoundation/autoware.universe/issues/2306#issuecomment-1317137743
Additionally, we’re discussing in this documentation PR conversation, so it’s better to return to your discussion space again if you'd like.
@miursh @aohsato could you review again please with the addition of A (azimuth) and D (distance) fields please?
Change commit: https://github.com/autowarefoundation/autoware-documentation/pull/180/commits/7e96d1a4b3b868788ac6c6535c15f04e097e2fa2
Updated doc link: https://autowarefoundation.github.io/autoware-documentation/pr-180/design/autoware-architecture/sensing/data-types/point-cloud/
@miursh @aohsato pls review <3