uncrustify ArduPlane/failsafe.pde

This commit is contained in:
uncrustify 2012-08-16 17:50:15 -07:00 committed by Pat Hickey
parent 4e795d4f1e
commit 326ca1b7cd

View File

@ -1,17 +1,17 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- // -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
/* /*
failsafe support * failsafe support
Andrew Tridgell, December 2011 * Andrew Tridgell, December 2011
*/ */
/* /*
our failsafe strategy is to detect main loop lockup and switch to * our failsafe strategy is to detect main loop lockup and switch to
passing inputs straight from the RC inputs to RC outputs. * passing inputs straight from the RC inputs to RC outputs.
*/ */
/* /*
this failsafe_check function is called from the core timer interrupt * this failsafe_check function is called from the core timer interrupt
at 1kHz. * at 1kHz.
*/ */
void failsafe_check(uint32_t tnow) void failsafe_check(uint32_t tnow)
{ {
@ -29,14 +29,14 @@ void failsafe_check(uint32_t tnow)
if (tnow - last_timestamp > 200000) { if (tnow - last_timestamp > 200000) {
// we have gone at least 0.2 seconds since the main loop // we have gone at least 0.2 seconds since the main loop
// ran. That means we're in trouble, or perhaps are in // ran. That means we're in trouble, or perhaps are in
// an initialisation routine or log erase. Start passing RC // an initialisation routine or log erase. Start passing RC
// inputs through to outputs // inputs through to outputs
in_failsafe = true; in_failsafe = true;
} }
if (in_failsafe && tnow - last_timestamp > 20000) { if (in_failsafe && tnow - last_timestamp > 20000) {
// pass RC inputs to outputs every 20ms // pass RC inputs to outputs every 20ms
last_timestamp = tnow; last_timestamp = tnow;
APM_RC.clearOverride(); APM_RC.clearOverride();
for (uint8_t ch=0; ch<8; ch++) { for (uint8_t ch=0; ch<8; ch++) {