mirror of https://github.com/ArduPilot/ardupilot
uncrustify ArduCopter/flip.pde
This commit is contained in:
parent
6088067ff3
commit
fef945e2cb
|
@ -17,10 +17,10 @@ static int8_t flip_dir;
|
|||
|
||||
void init_flip()
|
||||
{
|
||||
if(do_flip == false){
|
||||
if(do_flip == false) {
|
||||
do_flip = true;
|
||||
flip_state = 0;
|
||||
flip_dir = (ahrs.roll_sensor >= 0) ? 1 :-1;
|
||||
flip_dir = (ahrs.roll_sensor >= 0) ? 1 : -1;
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -32,9 +32,9 @@ void roll_flip()
|
|||
int32_t roll = ahrs.roll_sensor * flip_dir;
|
||||
|
||||
// Roll State machine
|
||||
switch (flip_state){
|
||||
switch (flip_state) {
|
||||
case 0:
|
||||
if (roll < 4500){
|
||||
if (roll < 4500) {
|
||||
// Roll control
|
||||
g.rc_1.servo_out = AAP_ROLL_OUT * flip_dir;
|
||||
g.rc_3.servo_out = g.rc_3.control_in + AAP_THR_INC;
|
||||
|
@ -44,7 +44,7 @@ void roll_flip()
|
|||
break;
|
||||
|
||||
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_3.servo_out = g.rc_3.control_in - AAP_THR_DEC;
|
||||
}else{
|
||||
|
@ -54,7 +54,7 @@ void roll_flip()
|
|||
break;
|
||||
|
||||
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_3.servo_out = g.rc_3.control_in + AAP_THR_INC;
|
||||
flip_timer++;
|
||||
|
|
Loading…
Reference in New Issue