mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 20:48:33 -04:00
Sub: base loop time remaining on variable loop rate
This commit is contained in:
parent
02a590024d
commit
b1516cc6e8
@ -146,8 +146,9 @@ void Sub::loop()
|
||||
// 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 + MAIN_LOOP_MICROS) - micros();
|
||||
scheduler.run(time_available > MAIN_LOOP_MICROS ? 0u : time_available);
|
||||
const uint32_t loop_us = scheduler.get_loop_period_us();
|
||||
const uint32_t time_available = (timer + loop_us) - micros();
|
||||
scheduler.run(time_available > loop_us ? 0u : time_available);
|
||||
}
|
||||
|
||||
|
||||
|
@ -41,7 +41,6 @@
|
||||
// run at 400Hz on all systems
|
||||
# define MAIN_LOOP_RATE 400
|
||||
# define MAIN_LOOP_SECONDS 0.0025f
|
||||
# define MAIN_LOOP_MICROS 2500
|
||||
|
||||
#ifndef SURFACE_DEPTH_DEFAULT
|
||||
# define SURFACE_DEPTH_DEFAULT -10.0f // pressure sensor reading 10cm depth means craft is considered surfaced
|
||||
|
Loading…
Reference in New Issue
Block a user