Plane: reduce height gain in auto landing for tiltrotors

avoid running the motors while tilted past the tilt max if we are in
AIRBRAKE state. This stops a large amount of forward thrust from the
tilted motors while trying to slow down, while still maintaining
attitude control
This commit is contained in:
Andrew Tridgell 2022-01-09 13:47:59 +11:00
parent b1d1dc97ff
commit 2846f87eeb
3 changed files with 41 additions and 8 deletions

View File

@ -2199,6 +2199,10 @@ void QuadPlane::vtol_position_controller(void)
poscontrol.last_run_ms = now_ms;
}
// avoid running the z controller in approach and airbrake if we're not already running it
// and tilt is more than tilt max
bool suppress_z_controller = false;
// horizontal position control
switch (poscontrol.get_state()) {
@ -2231,6 +2235,20 @@ void QuadPlane::vtol_position_controller(void)
aspeed = groundspeed;
}
if (tiltrotor.enabled() && poscontrol.get_state() == QPOS_AIRBRAKE) {
if ((now_ms - last_pidz_active_ms > 2000 && tiltrotor.tilt_over_max_angle()) ||
tiltrotor.current_tilt >= tiltrotor.get_fully_forward_tilt()) {
// use low throttle stabilization when airbraking on a
// tiltrotor. We don't want quite zero throttle as we
// want some drag, but don't want to run the Z
// controller which can result in high throttle on
// motors that are tilted forward, thus increasing
// speed
suppress_z_controller = true;
hold_stabilize(0.01);
}
}
// speed for crossover to POSITION1 controller
const float aspeed_threshold = MAX(plane.aparm.airspeed_min-2, assist_speed);
@ -2253,9 +2271,10 @@ void QuadPlane::vtol_position_controller(void)
const float stop_distance = stopping_distance();
if (poscontrol.get_state() == QPOS_AIRBRAKE && !(tiltrotor.enabled() && !tiltrotor.has_vtol_motor() && (tiltrotor.current_tilt >= tiltrotor.get_fully_forward_tilt()))) {
// don't ouput VTOL throttle on tiltrotors if there are no fixed VTOL motors and the tilt is still forward
if (!suppress_z_controller && poscontrol.get_state() == QPOS_AIRBRAKE) {
hold_hover(0);
// don't run Z controller again in this loop
suppress_z_controller = true;
}
/*
@ -2428,8 +2447,9 @@ void QuadPlane::vtol_position_controller(void)
// if continuous tiltrotor only advance to position 2 once tilts have finished moving
poscontrol.set_state(QPOS_POSITION2);
poscontrol.pilot_correction_done = false;
gcs().send_text(MAV_SEVERITY_INFO,"VTOL position2 started v=%.1f d=%.1f",
(double)ahrs.groundspeed(), (double)plane.auto_state.wp_distance);
gcs().send_text(MAV_SEVERITY_INFO,"VTOL position2 started v=%.1f d=%.1f h=%.1f",
(double)ahrs.groundspeed(), (double)plane.auto_state.wp_distance,
plane.relative_ground_altitude(plane.g.rangefinder_landing));
}
break;
}
@ -2601,8 +2621,14 @@ void QuadPlane::vtol_position_controller(void)
case QPOS_LAND_COMPLETE:
break;
}
run_z_controller();
/*
run the z controller unless something has already run it or set a target throttle
*/
if (!suppress_z_controller) {
// otherwise run z controller
run_z_controller();
}
if (now_ms - poscontrol.last_log_ms >= 40) {
// log poscontrol at 25Hz

View File

@ -530,8 +530,7 @@ void Tiltrotor::vectoring(void)
return;
}
float tilt_threshold = (max_angle_deg/90.0f);
bool no_yaw = (current_tilt > tilt_threshold);
const bool no_yaw = tilt_over_max_angle();
if (no_yaw) {
// fixed wing We need to apply inverse scaling with throttle, and remove the surface speed scaling as
// we don't want tilt impacted by airspeed
@ -674,4 +673,11 @@ bool Tiltrotor_Transition::show_vtol_view() const
return show_vtol;
}
// return true if we are tilted over the max angle threshold
bool Tiltrotor::tilt_over_max_angle(void) const
{
const float tilt_threshold = (max_angle_deg/90.0f);
return (current_tilt > MIN(tilt_threshold, get_forward_flight_tilt()));
}
#endif // HAL_QUADPLANE_ENABLED

View File

@ -42,6 +42,7 @@ public:
void bicopter_output();
void tilt_compensate_angle(float *thrust, uint8_t num_motors, float non_tilted_mul, float tilted_mul);
void tilt_compensate(float *thrust, uint8_t num_motors);
bool tilt_over_max_angle(void) const;
bool is_motor_tilting(uint8_t motor) const {
return (((uint8_t)tilt_mask.get()) & (1U<<motor));