Browse Source

indent correct

mission-4.1.18
Dr Gareth Owen 12 years ago committed by Randy Mackay
parent
commit
d9fc37c01c
  1. 6
      ArduCopter/ArduCopter.pde
  2. 12
      ArduCopter/control_modes.pde

6
ArduCopter/ArduCopter.pde

@ -1376,7 +1376,7 @@ bool set_yaw_mode(uint8_t new_yaw_mode)
} }
switch( 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 nav_yaw = ahrs.yaw_sensor; // store current yaw so we can start rotating back to correct one
case YAW_HOLD: case YAW_HOLD:
case YAW_ACRO: case YAW_ACRO:
@ -1450,8 +1450,8 @@ void update_yaw_mode(void)
} }
break; break;
case YAW_RESETTOARMEDYAW: case YAW_RESETTOARMEDYAW:
nav_yaw = get_yaw_slew(nav_yaw, initial_simple_bearing, AUTO_YAW_SLEW_RATE); nav_yaw = get_yaw_slew(nav_yaw, initial_simple_bearing, AUTO_YAW_SLEW_RATE);
get_stabilize_yaw(nav_yaw); get_stabilize_yaw(nav_yaw);
break; break;

12
ArduCopter/control_modes.pde

@ -91,12 +91,12 @@ static void do_aux_switch_function(int8_t ch_function, bool ch_flag)
} }
switch(tmp_function) { switch(tmp_function) {
case AUX_SWITCH_RESETTOARMEDYAW: case AUX_SWITCH_RESETTOARMEDYAW:
if(ch_flag) if(ch_flag)
set_yaw_mode(YAW_RESETTOARMEDYAW); set_yaw_mode(YAW_RESETTOARMEDYAW);
else else
set_yaw_mode(YAW_HOLD); set_yaw_mode(YAW_HOLD);
break; break;
case AUX_SWITCH_FLIP: case AUX_SWITCH_FLIP:
// flip if switch is on, positive throttle and we're actually flying // flip if switch is on, positive throttle and we're actually flying

Loading…
Cancel
Save