Skip to content

feat: support of Hesai FT120 sensor#412

Open
mgiardino-be wants to merge 20 commits intotier4:mainfrom
mgiardino-be:hesai_FT120
Open

feat: support of Hesai FT120 sensor#412
mgiardino-be wants to merge 20 commits intotier4:mainfrom
mgiardino-be:hesai_FT120

Conversation

@mgiardino-be
Copy link

PR Type

  • New Feature

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.

  • Assign PR to reviewer

Checklist for the PR Reviewer

Reviewers should check the checkboxes below before approval.

  • Commits are properly organized and messages are according to the guideline
  • (Optional) Unit tests have been written for new behavior
  • PR title describes the changes

Post-Review Checklist for the PR Author

PR Author should check the checkboxes below before merging.

  • All open points are addressed and tracked via issues or tickets

CI Checks

  • Build and test for PR: Required to pass before the merge.

mgiardino-be and others added 11 commits February 25, 2026 11:58
…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.
- 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.
@mojomex mojomex requested review from drwnz and mojomex February 27, 2026 02:03
@mgiardino-be mgiardino-be changed the title Support of Hesai FT120 sensor feat: Support of Hesai FT120 sensor Feb 27, 2026
@mgiardino-be mgiardino-be changed the title feat: Support of Hesai FT120 sensor feat: support of Hesai FT120 sensor Feb 27, 2026
@mojomex
Copy link
Collaborator

mojomex commented Mar 4, 2026

@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 pre-commit checks? 🙏

Copy link
Collaborator

@mojomex mojomex left a comment

Choose a reason for hiding this comment

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

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
Copy link
Collaborator

Choose a reason for hiding this comment

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

(unconfirmed) Given angluar azimuth resolution of 0.625deg, rounding down here could cause the last column to be filtered out.

Copy link
Collaborator

Choose a reason for hiding this comment

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

(Nebula would have to be changed to allow centi- or milli-degree settings here to fix this)

Copy link
Author

@mgiardino-be mgiardino-be Mar 16, 2026

Choose a reason for hiding this comment

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

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_ns to output_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
Copy link
Collaborator

Choose a reason for hiding this comment

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

(unconfirmed) might cause a column of points from an old scan to turn up in the new scan.

Copy link
Author

Choose a reason for hiding this comment

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

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.

Comment on lines +608 to +611
auto raw_ptr = buf.data();
col_count = raw_ptr[6];
row_count = raw_ptr[7];
resolution = raw_ptr[8];
Copy link
Collaborator

Choose a reason for hiding this comment

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

Raw pointer without bounds checking can cause a segfault or other corruption when an invalidly sized buffer is given. Prefer:

Suggested change
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]);
Copy link
Collaborator

Choose a reason for hiding this comment

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

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};
Copy link
Collaborator

Choose a reason for hiding this comment

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

(note for self) check

case SensorModel::HESAI_PANDAR128_E3X:
case SensorModel::HESAI_PANDAR128_E4X:
case SensorModel::HESAI_PANDARQT128:
case SensorModel::HESAI_PANDARFT120:
Copy link
Collaborator

Choose a reason for hiding this comment

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

Same as above

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;
Copy link
Collaborator

Choose a reason for hiding this comment

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

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
Copy link
Collaborator

Choose a reason for hiding this comment

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

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();
Copy link
Collaborator

Choose a reason for hiding this comment

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

Please name more descriptively, e.g. data or corrected_angle_data.

Copy link
Author

Choose a reason for hiding this comment

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

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;
Copy link
Collaborator

Choose a reason for hiding this comment

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

Please name this in snake_case, i.e. corrected_angle_data.

@codecov
Copy link

codecov bot commented Mar 16, 2026

Codecov Report

❌ Patch coverage is 0.41152% with 242 lines in your changes missing coverage. Please review.
✅ Project coverage is 35.94%. Comparing base (7a0b309) to head (979f640).
⚠️ Report is 2 commits behind head on main.

❌ 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     
Flag Coverage Δ
nebula 36.02% <0.41%> (?)
nebula_core_common 36.02% <0.41%> (?)
nebula_hesai 36.02% <0.41%> (?)
nebula_hesai_common 36.02% <0.41%> (?)
nebula_hesai_decoders 36.02% <0.41%> (?)
nebula_hesai_hw_interfaces 36.02% <0.41%> (?)

Flags with carried forward coverage won't be shown. Click here to find out more.

🚀 New features to boost your workflow:
  • ❄️ Test Analytics: Detect flaky tests, report on failures, and find test suite problems.

@mgiardino-be
Copy link
Author

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

I added some commits to apply your suggestions (and, meanwhile thinking about cloud_{min,max}_angle, I should have fixed a bug, in the latest commit). I'm waiting your suggestion for the last lines of hesai_common.hpp, please se my answers above.

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
MG

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

2 participants