Rover: use scheduler ticks in place of mainloop_count
This commit is contained in:
parent
e713802c24
commit
211e7416a9
@ -138,9 +138,6 @@ void Rover::loop()
|
||||
G_Dt = (timer - fast_loopTimer_us) * 1.0e-6f;
|
||||
fast_loopTimer_us = timer;
|
||||
|
||||
// for mainloop failure monitoring
|
||||
mainLoop_count++;
|
||||
|
||||
// tell the scheduler one tick has passed
|
||||
scheduler.tick();
|
||||
|
||||
|
@ -337,8 +337,6 @@ private:
|
||||
// System Timers
|
||||
// Time in microseconds of start of main control loop.
|
||||
uint32_t fast_loopTimer_us;
|
||||
// Counter of main loop executions. Used for performance monitoring and failsafe processing
|
||||
uint16_t mainLoop_count;
|
||||
|
||||
// set if we are driving backwards
|
||||
bool in_reverse;
|
||||
|
@ -16,13 +16,14 @@
|
||||
*/
|
||||
void Rover::failsafe_check()
|
||||
{
|
||||
static uint16_t last_mainLoop_count;
|
||||
static uint16_t last_ticks;
|
||||
static uint32_t last_timestamp;
|
||||
const uint32_t tnow = AP_HAL::micros();
|
||||
|
||||
if (mainLoop_count != last_mainLoop_count) {
|
||||
const uint16_t ticks = scheduler.ticks();
|
||||
if (ticks != last_ticks) {
|
||||
// the main loop is running, all is OK
|
||||
last_mainLoop_count = mainLoop_count;
|
||||
last_ticks = ticks;
|
||||
last_timestamp = tnow;
|
||||
return;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user