uncrustify ArduCopter/events.pde

This commit is contained in:
uncrustify 2012-08-16 17:50:02 -07:00 committed by Pat Hickey
parent f62681634b
commit bcad02a1ba

View File

@ -1,9 +1,9 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
/*
This event will be called when the failsafe changes
boolean failsafe reflects the current state
*/
* This event will be called when the failsafe changes
* boolean failsafe reflects the current state
*/
static void failsafe_on_event()
{
// This is how to handle a failsafe.
@ -22,7 +22,7 @@ static void failsafe_on_event()
break;
default:
if(home_is_set == true){
if(home_is_set == true) {
// same as above ^
// do_rtl sets the altitude to the current altitude by default
set_mode(RTL);
@ -43,7 +43,7 @@ static void failsafe_off_event()
if(control_mode == AUTO)
return;
if (g.throttle_fs_action == 2){
if (g.throttle_fs_action == 2) {
// We're back in radio contact
// return to AP
// ---------------------------
@ -53,7 +53,7 @@ static void failsafe_off_event()
reset_control_switch();
}else if (g.throttle_fs_action == 1){
}else if (g.throttle_fs_action == 1) {
// We're back in radio contact
// return to Home
// we should already be in RTL and throttle set to cruise
@ -86,8 +86,8 @@ static void update_events() // Used for MAV_CMD_DO_REPEAT_SERVO and MAV_CMD_DO_R
if(event_repeat == 0 || (millis() - event_timer) < event_delay)
return;
if (event_repeat > 0){
event_repeat --;
if (event_repeat > 0) {
event_repeat--;
}
if(event_repeat != 0) { // event_repeat = -1 means repeat forever