mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
GCS_MAVLink: ADSB msg bug: vert_velocity is supposed to be signed
- bug was introduced when changing from floating point to fixed point format
This commit is contained in:
parent
f0f3986f46
commit
7af717fead
@ -2783,7 +2783,7 @@
|
||||
<field type="int32_t" name="altitude">Altitude(ASL) in millimeters</field>
|
||||
<field type="uint16_t" name="heading">Course over ground in centidegrees</field>
|
||||
<field type="uint16_t" name="hor_velocity">The horizontal velocity in centimeters/second</field>
|
||||
<field type="uint16_t" name="ver_velocity">The vertical velocity in centimeters/second, positive is up</field>
|
||||
<field type="int16_t" name="ver_velocity">The vertical velocity in centimeters/second, positive is up</field>
|
||||
<field type="char[9]" name="callsign">The callsign, 8+null</field>
|
||||
<field type="uint8_t" name="emitter_type" enum="ADSB_EMITTER_TYPE">Type from ADSB_EMITTER_TYPE enum</field>
|
||||
<field type="uint8_t" name="tslc">Time since last communication in seconds</field>
|
||||
|
Loading…
Reference in New Issue
Block a user