From d9fc37c01ca7ed17f4e1824832c7378b25448281 Mon Sep 17 00:00:00 2001 From: Dr Gareth Owen Date: Mon, 20 May 2013 20:30:16 +0100 Subject: [PATCH] indent correct --- ArduCopter/ArduCopter.pde | 6 +++--- ArduCopter/control_modes.pde | 12 ++++++------ 2 files changed, 9 insertions(+), 9 deletions(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 688fad44c6..c35e57fd06 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -1376,7 +1376,7 @@ bool set_yaw_mode(uint8_t new_yaw_mode) } switch( new_yaw_mode ) { - case YAW_RESETTOARMEDYAW: + case YAW_RESETTOARMEDYAW: nav_yaw = ahrs.yaw_sensor; // store current yaw so we can start rotating back to correct one case YAW_HOLD: case YAW_ACRO: @@ -1450,8 +1450,8 @@ void update_yaw_mode(void) } break; - case YAW_RESETTOARMEDYAW: - nav_yaw = get_yaw_slew(nav_yaw, initial_simple_bearing, AUTO_YAW_SLEW_RATE); + case YAW_RESETTOARMEDYAW: + nav_yaw = get_yaw_slew(nav_yaw, initial_simple_bearing, AUTO_YAW_SLEW_RATE); get_stabilize_yaw(nav_yaw); break; diff --git a/ArduCopter/control_modes.pde b/ArduCopter/control_modes.pde index ef038c8742..ba01456008 100644 --- a/ArduCopter/control_modes.pde +++ b/ArduCopter/control_modes.pde @@ -91,12 +91,12 @@ static void do_aux_switch_function(int8_t ch_function, bool ch_flag) } switch(tmp_function) { - case AUX_SWITCH_RESETTOARMEDYAW: - if(ch_flag) - set_yaw_mode(YAW_RESETTOARMEDYAW); - else - set_yaw_mode(YAW_HOLD); - break; + case AUX_SWITCH_RESETTOARMEDYAW: + if(ch_flag) + set_yaw_mode(YAW_RESETTOARMEDYAW); + else + set_yaw_mode(YAW_HOLD); + break; case AUX_SWITCH_FLIP: // flip if switch is on, positive throttle and we're actually flying