mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
Fixes for Sim - Missing climb rate calculation
This commit is contained in:
parent
51c746c9a4
commit
31e05e40fd
@ -1210,8 +1210,10 @@ static void update_altitude()
|
||||
altitude_sensor = BARO;
|
||||
|
||||
#if HIL_MODE == HIL_MODE_ATTITUDE
|
||||
current_loc.alt = g_gps->altitude - gps_base_alt;
|
||||
return;
|
||||
current_loc.alt = g_gps->altitude - gps_base_alt;
|
||||
climb_rate = (g_gps->altitude - old_baro_alt) * 10;
|
||||
old_baro_alt = g_gps->altitude;
|
||||
return;
|
||||
#else
|
||||
|
||||
// calc the vertical accel rate
|
||||
|
@ -262,10 +262,10 @@ static void NOINLINE send_gps_status(mavlink_channel_t chan)
|
||||
mavlink_msg_gps_status_send(
|
||||
chan,
|
||||
g_gps->num_sats,
|
||||
NULL,
|
||||
NULL,
|
||||
NULL,
|
||||
NULL,
|
||||
next_WP.alt,
|
||||
nav_throttle,
|
||||
angle_boost,
|
||||
manual_boost,
|
||||
NULL);
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user