AP_IRLock_I2C: add comment on calibration equation

This commit is contained in:
Iampete1 2021-09-12 21:20:11 +01:00 committed by Randy Mackay
parent d62346f8d0
commit 66e1baa94c
1 changed files with 1 additions and 0 deletions

View File

@ -80,6 +80,7 @@ bool AP_IRLock_I2C::sync_frame_start(void)
/*
converts IRLOCK pixels to a position on a normal plane 1m in front of the lens
based on a characterization of IR-LOCK with the standard lens, focused such that 2.38mm of threads are exposed
see: https://github.com/ArduPilot/ardupilot/issues/5232 and https://gist.github.com/jschall/eac130ed9d6e5dcd9ce582f3eeeb3071
*/
void AP_IRLock_I2C::pixel_to_1M_plane(float pix_x, float pix_y, float &ret_x, float &ret_y)
{