mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 12:14:10 -04:00
SITL: LightwareSerial: return 130m when out-of-range-high
This commit is contained in:
parent
2dd3263650
commit
8843c17f9d
@ -50,5 +50,10 @@ void RF_LightWareSerial::update(float range)
|
||||
|
||||
uint32_t RF_LightWareSerial::packet_for_alt(uint16_t alt_cm, uint8_t *buffer, uint8_t buflen)
|
||||
{
|
||||
if (alt_cm > 10000) {
|
||||
// out-of-range-high
|
||||
alt_cm = 13000; // from datasheet
|
||||
}
|
||||
|
||||
return snprintf((char*)buffer, buflen, "%0.2f\r", alt_cm / 100.0f); // note tragic lack of snprintf return checking
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user