Skip to content

Commit

Permalink
Plane: fixed TECS state reset in VTOL auto
Browse files Browse the repository at this point in the history
this fixes a bug where TECS maintains its slow integrator while in a
VTOL hover mode in AUTO or GUIDED.

Among other things this affects PAYLOAD_PLACE and
DO_VTOL_TRANSITION. In those states the height can change while
hovering outside the control of TECS. When TECS regains control in a
fwd transition then can lead to a very large height loss or gain until
the TECS integrator can catch up
  • Loading branch information
tridge committed Jul 2, 2023
1 parent 670873d commit 086d090
Show file tree
Hide file tree
Showing 3 changed files with 37 additions and 2 deletions.
17 changes: 15 additions & 2 deletions ArduPlane/ArduPlane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -204,7 +204,13 @@ void Plane::ahrs_update()
*/
void Plane::update_speed_height(void)
{
if (control_mode->does_auto_throttle()) {
bool should_run_tecs = control_mode->does_auto_throttle();
#if HAL_QUADPLANE_ENABLED
if (quadplane.should_disable_TECS()) {
should_run_tecs = false;
}
#endif
if (should_run_tecs) {
// Call TECS 50Hz update. Note that we call this regardless of
// throttle suppressed, as this needs to be running for
// takeoff detection
Expand Down Expand Up @@ -538,7 +544,14 @@ void Plane::update_alt()
}
#endif

if (control_mode->does_auto_throttle() && !throttle_suppressed) {
bool should_run_tecs = control_mode->does_auto_throttle();
#if HAL_QUADPLANE_ENABLED
if (quadplane.should_disable_TECS()) {
should_run_tecs = false;
}
#endif

if (should_run_tecs && !throttle_suppressed) {

float distance_beyond_land_wp = 0;
if (flight_stage == AP_FixedWing::FlightStage::LAND &&
Expand Down
16 changes: 16 additions & 0 deletions ArduPlane/quadplane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -4560,4 +4560,20 @@ bool QuadPlane::allow_stick_mixing() const
return transition->allow_stick_mixing();
}

/*
return true if we should disable TECS in the current flight state
this ensures that TECS resets when we change height in a VTOL mode
*/
bool QuadPlane::should_disable_TECS() const
{
if (in_vtol_land_descent()) {
return true;
}
if (plane.control_mode == &plane.mode_guided &&
plane.auto_state.vtol_loiter) {
return true;
}
return false;
}

#endif // HAL_QUADPLANE_ENABLED
6 changes: 6 additions & 0 deletions ArduPlane/quadplane.h
Original file line number Diff line number Diff line change
Expand Up @@ -184,6 +184,12 @@ class QuadPlane
// Should we allow stick mixing from the pilot
bool allow_stick_mixing() const;

/*
should we disable the TECS controller?
only called when in an auto-throttle mode
*/
bool should_disable_TECS() const;

private:
AP_AHRS &ahrs;

Expand Down

0 comments on commit 086d090

Please sign in to comment.