uncrustify ArduCopter/flip.pde

This commit is contained in:
uncrustify 2012-08-16 17:50:03 -07:00 committed by Pat Hickey
parent 6088067ff3
commit fef945e2cb
1 changed files with 40 additions and 40 deletions

View File

@ -7,7 +7,7 @@
// Some states are fixed commands (until some IMU condition) // Some states are fixed commands (until some IMU condition)
// Some states include controls inside // Some states include controls inside
uint8_t flip_timer; uint8_t flip_timer;
uint8_t flip_state; uint8_t flip_state;
#define AAP_THR_INC 170 #define AAP_THR_INC 170
#define AAP_THR_DEC 120 #define AAP_THR_DEC 120
@ -17,51 +17,51 @@ static int8_t flip_dir;
void init_flip() void init_flip()
{ {
if(do_flip == false){ if(do_flip == false) {
do_flip = true; do_flip = true;
flip_state = 0; flip_state = 0;
flip_dir = (ahrs.roll_sensor >= 0) ? 1 :-1; flip_dir = (ahrs.roll_sensor >= 0) ? 1 : -1;
} }
} }
void roll_flip() void roll_flip()
{ {
// Pitch // Pitch
g.rc_2.servo_out = get_stabilize_pitch(g.rc_2.control_in); g.rc_2.servo_out = get_stabilize_pitch(g.rc_2.control_in);
int32_t roll = ahrs.roll_sensor * flip_dir; int32_t roll = ahrs.roll_sensor * flip_dir;
// Roll State machine // Roll State machine
switch (flip_state){ switch (flip_state) {
case 0: case 0:
if (roll < 4500){ if (roll < 4500) {
// Roll control // Roll control
g.rc_1.servo_out = AAP_ROLL_OUT * flip_dir; g.rc_1.servo_out = AAP_ROLL_OUT * flip_dir;
g.rc_3.servo_out = g.rc_3.control_in + AAP_THR_INC; g.rc_3.servo_out = g.rc_3.control_in + AAP_THR_INC;
}else{ }else{
flip_state++; flip_state++;
} }
break; break;
case 1: case 1:
if((roll >= 4500) || (roll < -9000)){ if((roll >= 4500) || (roll < -9000)) {
g.rc_1.servo_out = get_rate_roll(40000 * flip_dir); g.rc_1.servo_out = get_rate_roll(40000 * flip_dir);
g.rc_3.servo_out = g.rc_3.control_in - AAP_THR_DEC; g.rc_3.servo_out = g.rc_3.control_in - AAP_THR_DEC;
}else{ }else{
flip_state++; flip_state++;
flip_timer = 0; flip_timer = 0;
} }
break; break;
case 2: case 2:
if (flip_timer < 100){ if (flip_timer < 100) {
g.rc_1.servo_out = get_stabilize_roll(g.rc_1.control_in); g.rc_1.servo_out = get_stabilize_roll(g.rc_1.control_in);
g.rc_3.servo_out = g.rc_3.control_in + AAP_THR_INC; g.rc_3.servo_out = g.rc_3.control_in + AAP_THR_INC;
flip_timer++; flip_timer++;
}else{ }else{
do_flip = false; do_flip = false;
flip_state = 0; flip_state = 0;
} }
break; break;
} }
} }