diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 9ad705ba1d..447d610404 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -954,12 +954,14 @@ void loop() // tell the scheduler one tick has passed scheduler.tick(); - } else { - uint16_t dt = timer - fast_loopTimer; - if (dt < 10000) { - uint16_t time_to_next_loop = 10000 - dt; - scheduler.run(time_to_next_loop); - } + + // run all the tasks that are due to run. Note that we only + // have to call this once per loop, as the tasks are scheduled + // in multiples of the main loop tick. So if they don't run on + // the first call to the scheduler they won't run on a later + // call until scheduler.tick() is called again + uint32_t time_available = (timer + 10000) - micros(); + scheduler.run(time_available - 500); } } diff --git a/ArduCopter/GCS_Mavlink.pde b/ArduCopter/GCS_Mavlink.pde index 3fc1e83a6f..ed8f09a267 100644 --- a/ArduCopter/GCS_Mavlink.pde +++ b/ArduCopter/GCS_Mavlink.pde @@ -199,7 +199,7 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan, uint16_t pack control_sensors_present, control_sensors_enabled, control_sensors_health, - 0, // CPU Load not supported in AC yet + (uint16_t)(scheduler.load_average(10000) * 1000), battery_voltage1 * 1000, // mV battery_current, // in 10mA units battery_remaining, // in %