mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-26 18:48:30 -04:00
AP_ADSB: bugfix vertical velocity sign was backwards
This commit is contained in:
parent
02dc42275c
commit
6107dcc8e7
@ -69,7 +69,7 @@ void AP_ADSB_uAvionix_MAVLink::send_dynamic_out(const mavlink_channel_t chan) co
|
||||
const int32_t latitude = _frontend._my_loc.lat;
|
||||
const int32_t longitude = _frontend._my_loc.lng;
|
||||
const int32_t altGNSS = _frontend._my_loc.alt * 10; // convert cm to mm
|
||||
const int16_t velVert = gps_velocity.z * 1E2; // convert m/s to cm/s
|
||||
const int16_t velVert = -1.0f * gps_velocity.z * 1E2; // convert m/s to cm/s
|
||||
const int16_t nsVog = gps_velocity.x * 1E2; // convert m/s to cm/s
|
||||
const int16_t ewVog = gps_velocity.y * 1E2; // convert m/s to cm/s
|
||||
const uint8_t fixType = gps.status(); // this lines up perfectly with our enum
|
||||
|
@ -364,7 +364,7 @@ void AP_ADSB_uAvionix_UCP::send_GPS_Data()
|
||||
msg.verticalVelocityFOM_mmps = msg.horizontalVelocityFOM_mmps;
|
||||
|
||||
// Velocities
|
||||
msg.verticalVelocity_cmps = fix_is_good ? velocity.z * 1E2 : INT16_MAX;
|
||||
msg.verticalVelocity_cmps = fix_is_good ? -1.0f * velocity.z * 1E2 : INT16_MAX;
|
||||
msg.northVelocity_mmps = fix_is_good ? velocity.x * 1E3 : INT32_MAX;
|
||||
msg.eastVelocity_mmps = fix_is_good ? velocity.y * 1E3 : INT32_MAX;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user