mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Sub: Update land mode to move up instead of down.
This commit is contained in:
parent
e805dd5e30
commit
b08e1e6919
@ -215,10 +215,10 @@ float Sub::get_land_descent_speed()
|
||||
bool sonar_ok = false;
|
||||
#endif
|
||||
// if we are above 10m and the sonar does not sense anything perform regular alt hold descent
|
||||
if (pos_control.get_pos_target().z >= pv_alt_above_origin(LAND_START_ALT) && !(sonar_ok && sonar_alt_health >= SONAR_ALT_HEALTH_MAX)) {
|
||||
return pos_control.get_speed_down();
|
||||
if (pos_control.get_pos_target().z <= pv_alt_above_origin(LAND_START_ALT) && !(sonar_ok && sonar_alt_health >= SONAR_ALT_HEALTH_MAX)) {
|
||||
return pos_control.get_speed_up();
|
||||
}else{
|
||||
return -abs(g.land_speed);
|
||||
return abs(g.land_speed);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -24,7 +24,7 @@ void Sub::update_land_and_crash_detectors()
|
||||
// called at MAIN_LOOP_RATE
|
||||
void Sub::update_land_detector()
|
||||
{
|
||||
if(barometer.get_altitude() > SURFACE_END_DEPTH && ap.throttle_zero) {
|
||||
if(barometer.num_instances() > 1 && barometer.get_altitude() > SURFACE_END_DEPTH && ap.throttle_zero) {
|
||||
set_land_complete(true);
|
||||
} else {
|
||||
set_land_complete(false);
|
||||
|
Loading…
Reference in New Issue
Block a user