Sub: use scheduler ticks in place of mainloop_count
This commit is contained in:
parent
7f69c5d26d
commit
9bb1224cef
@ -129,9 +129,6 @@ void Sub::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();
|
||||||
|
@ -53,7 +53,6 @@ Sub::Sub(void)
|
|||||||
circle_nav(inertial_nav, ahrs_view, pos_control),
|
circle_nav(inertial_nav, ahrs_view, pos_control),
|
||||||
pmTest1(0),
|
pmTest1(0),
|
||||||
fast_loopTimer(0),
|
fast_loopTimer(0),
|
||||||
mainLoop_count(0),
|
|
||||||
in_mavlink_delay(false),
|
in_mavlink_delay(false),
|
||||||
param_loader(var_info),
|
param_loader(var_info),
|
||||||
last_pilot_yaw_input_ms(0)
|
last_pilot_yaw_input_ms(0)
|
||||||
|
@ -405,8 +405,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;
|
|
||||||
|
|
||||||
// Reference to the relay object
|
// Reference to the relay object
|
||||||
AP_Relay relay;
|
AP_Relay relay;
|
||||||
|
@ -6,7 +6,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;
|
||||||
|
|
||||||
@ -30,9 +30,10 @@ void Sub::mainloop_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
Block a user