mirror of https://github.com/ArduPilot/ardupilot
moved detector to run until the throttle is low, then stop running.
This commit is contained in:
parent
f0456dc947
commit
bc578172a5
|
@ -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;
|
||||||
|
|
Loading…
Reference in New Issue