AP_RangeFinder: Clarify the purpose of input registers

This commit is contained in:
murata 2017-11-27 22:14:17 +09:00 committed by Francisco Ferreira
parent 5239d86d13
commit 851ee24c99

View File

@ -164,11 +164,10 @@ bool AP_RangeFinder_LeddarOne::CRC16(uint8_t *aBuffer, uint8_t aLength, bool aCh
-----------------------------------------------
0: slave address (LEDDARONE_DEFAULT_ADDRESS)
1: functions code
2: ?
3-4-5-6: timestamp
2: byte count
5-6-3-4: timestamp
7-8: internal temperature
9: ?
10: number of detections
9-10: number of detections
11-12: first distance
13-14: first amplitude
15-16: second distance