changed the way takeoff complete is figured. Looking for high throttle.

This commit is contained in:
Jason Short 2012-05-29 11:19:28 -07:00
parent b8349f5486
commit 09f4a16bfb
1 changed files with 6 additions and 4 deletions

View File

@ -1624,11 +1624,13 @@ void update_throttle_mode(void)
}
#endif
// Code to manage the Copter state
if ((millis() - takeoff_timer) > 5000){
if (takeoff_complete == false && motors.armed()){
if ((g.rc_3.control_in > g.throttle_cruise)){
// we must be in the air by now
takeoff_complete = true;
}
}
}else{
// we are on the ground
takeoff_complete = false;