Browse Source

Sub: use scheduler ticks in place of mainloop_count

mission-4.1.18
Peter Barker 7 years ago committed by Andrew Tridgell
parent
commit
9bb1224cef
  1. 3
      ArduSub/ArduSub.cpp
  2. 1
      ArduSub/Sub.cpp
  3. 2
      ArduSub/Sub.h
  4. 7
      ArduSub/failsafe.cpp

3
ArduSub/ArduSub.cpp

@ -129,9 +129,6 @@ void Sub::loop() @@ -129,9 +129,6 @@ void Sub::loop()
G_Dt = (float)(timer - fast_loopTimer) / 1000000.0f;
fast_loopTimer = timer;
// for mainloop failure monitoring
mainLoop_count++;
// Execute the fast loop
// ---------------------
fast_loop();

1
ArduSub/Sub.cpp

@ -53,7 +53,6 @@ Sub::Sub(void) @@ -53,7 +53,6 @@ Sub::Sub(void)
circle_nav(inertial_nav, ahrs_view, pos_control),
pmTest1(0),
fast_loopTimer(0),
mainLoop_count(0),
in_mavlink_delay(false),
param_loader(var_info),
last_pilot_yaw_input_ms(0)

2
ArduSub/Sub.h

@ -405,8 +405,6 @@ private: @@ -405,8 +405,6 @@ private:
// --------------
// Time in microseconds of main control loop
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
AP_Relay relay;

7
ArduSub/failsafe.cpp

@ -6,7 +6,7 @@ @@ -6,7 +6,7 @@
*/
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 bool in_failsafe;
@ -30,9 +30,10 @@ void Sub::mainloop_failsafe_check() @@ -30,9 +30,10 @@ void Sub::mainloop_failsafe_check()
{
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
failsafe_last_mainLoop_count = mainLoop_count;
failsafe_last_ticks = ticks;
failsafe_last_timestamp = tnow;
if (in_failsafe) {
in_failsafe = false;

Loading…
Cancel
Save