mirror of https://github.com/ArduPilot/ardupilot
Copter: use scheduler ticks in place of mainloop_count
This commit is contained in:
parent
211e7416a9
commit
7f69c5d26d
|
@ -226,9 +226,6 @@ void Copter::loop()
|
||||||
G_Dt = (float)(timer - fast_loopTimer) / 1000000.0f;
|
G_Dt = (float)(timer - fast_loopTimer) / 1000000.0f;
|
||||||
fast_loopTimer = timer;
|
fast_loopTimer = timer;
|
||||||
|
|
||||||
// for mainloop failure monitoring
|
|
||||||
mainLoop_count++;
|
|
||||||
|
|
||||||
// Execute the fast loop
|
// Execute the fast loop
|
||||||
// ---------------------
|
// ---------------------
|
||||||
fast_loop();
|
fast_loop();
|
||||||
|
|
|
@ -48,7 +48,6 @@ Copter::Copter(void)
|
||||||
inertial_nav(ahrs),
|
inertial_nav(ahrs),
|
||||||
pmTest1(0),
|
pmTest1(0),
|
||||||
fast_loopTimer(0),
|
fast_loopTimer(0),
|
||||||
mainLoop_count(0),
|
|
||||||
auto_trim_counter(0),
|
auto_trim_counter(0),
|
||||||
in_mavlink_delay(false),
|
in_mavlink_delay(false),
|
||||||
param_loader(var_info),
|
param_loader(var_info),
|
||||||
|
|
|
@ -479,8 +479,6 @@ private:
|
||||||
// --------------
|
// --------------
|
||||||
// Time in microseconds of main control loop
|
// Time in microseconds of main control loop
|
||||||
uint32_t fast_loopTimer;
|
uint32_t fast_loopTimer;
|
||||||
// Counter of main loop executions. Used for performance monitoring and failsafe processing
|
|
||||||
uint16_t mainLoop_count;
|
|
||||||
// arm_time_ms - Records when vehicle was armed. Will be Zero if we are disarmed.
|
// arm_time_ms - Records when vehicle was armed. Will be Zero if we are disarmed.
|
||||||
uint32_t arm_time_ms;
|
uint32_t arm_time_ms;
|
||||||
|
|
||||||
|
|
|
@ -8,7 +8,7 @@
|
||||||
//
|
//
|
||||||
|
|
||||||
static bool failsafe_enabled = false;
|
static bool failsafe_enabled = false;
|
||||||
static uint16_t failsafe_last_mainLoop_count;
|
static uint16_t failsafe_last_ticks;
|
||||||
static uint32_t failsafe_last_timestamp;
|
static uint32_t failsafe_last_timestamp;
|
||||||
static bool in_failsafe;
|
static bool in_failsafe;
|
||||||
|
|
||||||
|
@ -36,9 +36,10 @@ void Copter::failsafe_check()
|
||||||
{
|
{
|
||||||
uint32_t tnow = AP_HAL::micros();
|
uint32_t tnow = AP_HAL::micros();
|
||||||
|
|
||||||
if (mainLoop_count != failsafe_last_mainLoop_count) {
|
const uint16_t ticks = scheduler.ticks();
|
||||||
|
if (ticks != failsafe_last_ticks) {
|
||||||
// the main loop is running, all is OK
|
// the main loop is running, all is OK
|
||||||
failsafe_last_mainLoop_count = mainLoop_count;
|
failsafe_last_ticks = ticks;
|
||||||
failsafe_last_timestamp = tnow;
|
failsafe_last_timestamp = tnow;
|
||||||
if (in_failsafe) {
|
if (in_failsafe) {
|
||||||
in_failsafe = false;
|
in_failsafe = false;
|
||||||
|
|
Loading…
Reference in New Issue