Copter: fixed load average for different loop rates

Pair-Programmed-With: Paul Riseborough <p_riseborough@live.com.au>
This commit is contained in:
Andrew Tridgell 2014-04-04 21:37:56 +11:00
parent 07d621c4be
commit 339689b578
1 changed files with 1 additions and 1 deletions

View File

@ -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 %