mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
uncrustify ArduPlane/failsafe.pde
This commit is contained in:
parent
4e795d4f1e
commit
326ca1b7cd
@ -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)
|
||||||
{
|
{
|
||||||
|
Loading…
Reference in New Issue
Block a user