From 339689b578dbb4086388eee61438e7937a2b7bb4 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 4 Apr 2014 21:37:56 +1100 Subject: [PATCH] Copter: fixed load average for different loop rates Pair-Programmed-With: Paul Riseborough --- ArduCopter/GCS_Mavlink.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/GCS_Mavlink.pde b/ArduCopter/GCS_Mavlink.pde index 915dc0a13a..5033f34d59 100644 --- a/ArduCopter/GCS_Mavlink.pde +++ b/ArduCopter/GCS_Mavlink.pde @@ -211,7 +211,7 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan) control_sensors_present, control_sensors_enabled, control_sensors_health, - (uint16_t)(scheduler.load_average(10000) * 1000), + (uint16_t)(scheduler.load_average(MAIN_LOOP_MICROS) * 1000), battery.voltage() * 1000, // mV battery_current, // in 10mA units battery_remaining, // in %