mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Plane: Quadplane: allow servo auto trim for motors only tailsitter assist
This commit is contained in:
parent
1e3e5e5577
commit
821053e580
@ -4275,4 +4275,28 @@ void QuadPlane::disable_yaw_rate_time_constant()
|
||||
attitude_control->set_yaw_rate_tc(0.0);
|
||||
}
|
||||
|
||||
// Check if servo auto trim is allowed, only if countrol surfaces are fully in use
|
||||
bool QuadPlane::allow_servo_auto_trim()
|
||||
{
|
||||
if (!available()) {
|
||||
// Quadplane disabled, auto trim always allowed
|
||||
return true;
|
||||
}
|
||||
if (in_vtol_mode()) {
|
||||
// VTOL motors active in VTOL modes
|
||||
return false;
|
||||
}
|
||||
if (!in_assisted_flight()) {
|
||||
// In forward flight and VTOL motors not active
|
||||
return true;
|
||||
}
|
||||
if (tailsitter.enabled() && ((options & QuadPlane::OPTION_TAILSIT_Q_ASSIST_MOTORS_ONLY) != 0)) {
|
||||
// Tailsitter in forward flight, motors providing active stabalisation with motors only option
|
||||
// Control surfaces are running as normal with I term active, motor I term is zeroed
|
||||
return true;
|
||||
}
|
||||
// In forward flight with active VTOL motors
|
||||
return false;
|
||||
}
|
||||
|
||||
#endif // HAL_QUADPLANE_ENABLED
|
||||
|
@ -168,6 +168,9 @@ public:
|
||||
// called when we change mode (for any mode, not just Q modes)
|
||||
void mode_enter(void);
|
||||
|
||||
// Check if servo auto trim is allowed
|
||||
bool allow_servo_auto_trim();
|
||||
|
||||
private:
|
||||
AP_AHRS &ahrs;
|
||||
AP_Vehicle::MultiCopter aparm;
|
||||
|
@ -1037,7 +1037,7 @@ void Plane::servos_auto_trim(void)
|
||||
return;
|
||||
}
|
||||
#if HAL_QUADPLANE_ENABLED
|
||||
if (quadplane.in_assisted_flight() || quadplane.in_vtol_mode()) {
|
||||
if (!quadplane.allow_servo_auto_trim()) {
|
||||
// can't auto-trim with quadplane motors running
|
||||
return;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user