moved detector to run until the throttle is low, then stop running.

This commit is contained in:
Jason Short 2012-05-30 09:44:59 -07:00
parent f0456dc947
commit bc578172a5
1 changed files with 2 additions and 2 deletions

View File

@ -424,9 +424,9 @@ static bool verify_land_sonar()
if(ground_detector < 30) { if(ground_detector < 30) {
ground_detector++; ground_detector++;
}else if (ground_detector == 30){ }else if (ground_detector == 30){
ground_detector++;
land_complete = true; land_complete = true;
if(g.rc_3.control_in == 0){ if(g.rc_3.control_in == 0){
ground_detector++;
init_disarm_motors(); init_disarm_motors();
} }
return true; return true;
@ -458,9 +458,9 @@ static bool verify_land_baro()
if(ground_detector < 30) { if(ground_detector < 30) {
ground_detector++; ground_detector++;
}else if (ground_detector == 30){ }else if (ground_detector == 30){
ground_detector++;
land_complete = true; land_complete = true;
if(g.rc_3.control_in == 0){ if(g.rc_3.control_in == 0){
ground_detector++;
init_disarm_motors(); init_disarm_motors();
} }
return true; return true;