Arducopter: Flip mode

Flip mode graduates to pre-compiled option
This commit is contained in:
Jason Short 2012-07-18 22:35:38 -07:00
parent c5d3620d2b
commit 095a9c5c96
1 changed files with 1 additions and 4 deletions

View File

@ -613,9 +613,7 @@ static struct Location circle_WP;
//////////////////////////////////////////////////////////////////////////////// ////////////////////////////////////////////////////////////////////////////////
// Used to enable Jose's flip code // Used to enable Jose's flip code
// when true the Roll/Pitch/Throttle control is sent to the flip state machine // when true the Roll/Pitch/Throttle control is sent to the flip state machine
#if CH7_OPTION == CH7_FLIP
static bool do_flip = false; static bool do_flip = false;
#endif
// Used to track the CH7 toggle state. // Used to track the CH7 toggle state.
// When CH7 goes LOW PWM from HIGH PWM, this value will have been set true // When CH7 goes LOW PWM from HIGH PWM, this value will have been set true
// This allows advanced functionality to know when to execute // This allows advanced functionality to know when to execute
@ -1611,16 +1609,15 @@ void update_roll_pitch_mode(void)
// hack to do auto_flip - need to remove, no one is using. // hack to do auto_flip - need to remove, no one is using.
#if CH7_OPTION == CH7_FLIP
if (do_flip){ if (do_flip){
if(g.rc_1.control_in == 0){ if(g.rc_1.control_in == 0){
roll_flip(); roll_flip();
return; return;
}else{ }else{
// force an exit from the loop if we are not hands off sticks.
do_flip = false; do_flip = false;
} }
} }
#endif
switch(roll_pitch_mode){ switch(roll_pitch_mode){
case ROLL_PITCH_ACRO: case ROLL_PITCH_ACRO: