feat: support of Hesai FT120 sensor#412
Conversation
…ion binary file. Added calibration file from a sensor.
Added definitions for message tail, data packet and FT120 sensor.
…tatus structure that can be reused (is the same as for AT128 and QT128 sensors). Integrated the sensor in the HW interface.
…tion for each pixel.
- it uses old ScanCutAngles approac (not a big deal due to limited FoV); - dual return works, but manual recommends to use only single return modes; - maybe a couple of "if" in unpack and convert_returns can be simplified; -mask filter was not tested.
Include the new sensor in the driver source, with the correct decoder selection.
|
@mgiardino-be Thank you for the PR, looks very good already! I will finish my review by end of this week. In the meantime, could you check and address the failing |
mojomex
left a comment
There was a problem hiding this comment.
Hi, sorry for the super long wait 🙇
The code looks pretty good! I've left a few small comments here and there. Since this is the first solid state Hesai LiDAR in Nebula, we'll have to reconsider parameter handling since cloud_{min,max}_angle and a few other params are now obsolete. It's fine as it is in this PR though!
The reason we took so long is that we got word from Hesai that FT120 has been end-of-lifed (there is some public info on the web about this).
Our projects are moving to FTX, and the implementation is different again to the FT120, so we are currently discussing if we still want to merge and maintain your FT120 PR.
We'll let you know ASAP when we have clarity on how to move forward. In the meantime, I want to thank you again for the contribution and apologize that we are only considering this issue after you already went through the trouble of preparing your PR!
FYI @drwnz
| min_range: 0.3 | ||
| max_range: 22.0 | ||
| cloud_min_angle: 40 | ||
| cloud_max_angle: 139 |
There was a problem hiding this comment.
(unconfirmed) Given angluar azimuth resolution of 0.625deg, rounding down here could cause the last column to be filtered out.
There was a problem hiding this comment.
(Nebula would have to be changed to allow centi- or milli-degree settings here to fix this)
There was a problem hiding this comment.
I should think how to verify the issue.
Relevant part is at the end of hesai_decoder.hpp.
- we received a packet for which passed_timestamp_reset_angle()==true (a new scan)
- we should always assign
new_scan_timestamp_nstooutput_frame_, as we are processing a new scan but the buffers are not swapped yet;
For this reason, we should always impose that cut_angle != cloud_max_angle: due to inner working of the sensor, it made no sense to have a cut_angle which is not associated to the sensor minimum (= transmit old decode frame when we start processing a new one) or maximum column (we have completed one frame, send it). If cut_angle != cloud_max_angle, the timestamp is going to be assigned to output_frame_ and the procedure should be correct.
| cloud_min_angle: 40 | ||
| cloud_max_angle: 139 | ||
| sync_angle: 40 # 40-139 | ||
| cut_angle: 139.0 |
There was a problem hiding this comment.
(unconfirmed) might cause a column of points from an old scan to turn up in the new scan.
There was a problem hiding this comment.
This is linked to above comment.
Worse, there is a bug in the code (at line 575 in hesai_decoder.hpp) so that the first column of a new scan is written into the frame for the old one: I'll apply a bugfix.
| auto raw_ptr = buf.data(); | ||
| col_count = raw_ptr[6]; | ||
| row_count = raw_ptr[7]; | ||
| resolution = raw_ptr[8]; |
There was a problem hiding this comment.
Raw pointer without bounds checking can cause a segfault or other corruption when an invalidly sized buffer is given. Prefer:
| auto raw_ptr = buf.data(); | |
| col_count = raw_ptr[6]; | |
| row_count = raw_ptr[7]; | |
| resolution = raw_ptr[8]; | |
| col_count = raw_ptr.at(6); | |
| row_count = raw_ptr.at(7); | |
| resolution = raw_ptr.at(8); |
| const auto count{col_count * row_count}; | ||
| const auto count_bytes{4 * count}; | ||
|
|
||
| auto ref = &(buf[9]); |
There was a problem hiding this comment.
Perform size checking here (are there really count_bytes after the given offset?)
| [[nodiscard]] std::tuple<float, float> get_fov_padding() const override | ||
| { | ||
| // For FT120 should be enough | ||
| return {-0.1, 0.1}; |
| case SensorModel::HESAI_PANDAR128_E3X: | ||
| case SensorModel::HESAI_PANDAR128_E4X: | ||
| case SensorModel::HESAI_PANDARQT128: | ||
| case SensorModel::HESAI_PANDARFT120: |
| uint16_t row_num; // 120 | ||
| uint8_t column_res; // 63, to be multiplied by standard coefficient of 0.01° | ||
| uint8_t row_res; // 63, to be multiplied by standard coefficient of 0.01° | ||
| uint8_t return_num; // 0, single return, 1 dual return & block 1 returns first type of dual mode; |
There was a problem hiding this comment.
The manual calls this field "first_block_return", might be good to align with that
| uint8_t factory_information; // fixed, 0x42 | ||
| uint32_t udp_sequence; | ||
| uint32_t crc_tail; | ||
| uint32_t |
There was a problem hiding this comment.
uint8_t signature[16] might be more idiomatic since it's just a long number, not a sequence of 4 ints.
|
|
||
| ++calib_i; | ||
|
|
||
| auto C = CorrectedAngleData(); |
There was a problem hiding this comment.
Please name more descriptively, e.g. data or corrected_angle_data.
There was a problem hiding this comment.
I'm changing it to pixel_angle_data, to avoid problems with corrected_angle_data.
| : public AngleCorrector<HesaiSolidStateCalibration, ColumnN> | ||
| { | ||
| private: | ||
| std::array<std::array<CorrectedAngleData, RowN>, ColumnN> correctedAngleData; |
There was a problem hiding this comment.
Please name this in snake_case, i.e. corrected_angle_data.
Codecov Report❌ Patch coverage is ❌ Your patch check has failed because the patch coverage (0.00%) is below the target coverage (90.00%). You can increase the patch coverage or adjust the target coverage. Additional details and impacted files@@ Coverage Diff @@
## main #412 +/- ##
==========================================
- Coverage 36.75% 35.94% -0.81%
==========================================
Files 138 140 +2
Lines 11207 11461 +254
Branches 5960 6047 +87
==========================================
+ Hits 4119 4120 +1
- Misses 6301 6549 +248
- Partials 787 792 +5
Flags with carried forward coverage won't be shown. Click here to find out more. 🚀 New features to boost your workflow:
|
…w scan is received.
I added some commits to apply your suggestions (and, meanwhile thinking about For FT120 end-of-life, also our vendor told us the same information, so it is understandable if the PR will not be merged. I'm curious, do you already know how Hesai has changed the packet structure in the new FTX sensor? Maybe it is possible to adapt part of our work (at least, a little hope... 😁). Have a nice day |
PR Type
Related Links
GitHub Issue 410
Description
Add support for Hesai FT120 solid state sensor.
Review Procedure
Remarks
Pre-Review Checklist for the PR Author
PR Author should check the checkboxes below when creating the PR.
Checklist for the PR Reviewer
Reviewers should check the checkboxes below before approval.
Post-Review Checklist for the PR Author
PR Author should check the checkboxes below before merging.
CI Checks