mirror of https://github.com/ArduPilot/ardupilot
Plane: Quadplane disable forward motor assist in Q modes if rangefinder is out of range low
This commit is contained in:
parent
97e7b48ca1
commit
8ebe64a274
|
@ -3209,8 +3209,9 @@ int8_t QuadPlane::forward_throttle_pct()
|
|||
// lidar could cause the aircraft not to be able to
|
||||
// approach the landing point when landing below the takeoff point
|
||||
vel_forward.last_pct = vel_forward.integrator;
|
||||
} else if (in_vtol_land_final() && motors->limit.throttle_lower) {
|
||||
// we're in the settling phase of landing, disable fwd motor
|
||||
} else if ((in_vtol_land_final() && motors->limit.throttle_lower) ||
|
||||
(plane.g.rangefinder_landing && (plane.rangefinder.status_orient(ROTATION_PITCH_270) == RangeFinder::Status::OutOfRangeLow))) {
|
||||
// we're in the settling phase of landing or using a rangefinder that is out of range low, disable fwd motor
|
||||
vel_forward.last_pct = 0;
|
||||
vel_forward.integrator = 0;
|
||||
} else {
|
||||
|
|
Loading…
Reference in New Issue