mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-08 08:53:56 -04:00
AP_RangeFinder: Modified uLanding parse to check device version.
US-D1 version ID was changed to 2 from 0. This alteration will prevent past US-D1s, with version ID 0, from being 3-byte parsed.
This commit is contained in:
parent
19ace7cace
commit
a1557184d5
@ -174,7 +174,7 @@ bool AP_RangeFinder_uLanding::get_reading(uint16_t &reading_cm)
|
|||||||
*/
|
*/
|
||||||
continue;
|
continue;
|
||||||
} else {
|
} else {
|
||||||
if (_version == 0) {
|
if (_version == 0 && _header != ULANDING_HDR) {
|
||||||
// parse data for Firmware Version #0
|
// parse data for Firmware Version #0
|
||||||
sum += (_linebuf[2]&0x7F)*128 + (_linebuf[1]&0x7F);
|
sum += (_linebuf[2]&0x7F)*128 + (_linebuf[1]&0x7F);
|
||||||
count++;
|
count++;
|
||||||
@ -199,7 +199,7 @@ bool AP_RangeFinder_uLanding::get_reading(uint16_t &reading_cm)
|
|||||||
|
|
||||||
reading_cm = sum / count;
|
reading_cm = sum / count;
|
||||||
|
|
||||||
if (_version == 0) {
|
if (_version == 0 && _header != ULANDING_HDR) {
|
||||||
reading_cm *= 2.5f;
|
reading_cm *= 2.5f;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user