mirror of https://github.com/ArduPilot/ardupilot
Copter: use the new scheduler load_average() call
this also simplifies the main loop
This commit is contained in:
parent
62cc84aba3
commit
01e19a32fe
|
@ -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);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -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 %
|
||||
|
|
Loading…
Reference in New Issue