ardupilot
ardupilot copied to clipboard
Improve VTOL to FW transition behaviour for tilt rotor airframes
During this development a bug that resulted in the forward pitch limit specified by Q_FWD_PIT_LIM not being applied to the tilt rotor airframe pitch was discovered and fixed - see https://github.com/ArduPilot/ardupilot/commit/e0bc77bdfbbd7990d72550944ebec48f9a9f9f28. This bug was introduced when https://github.com/ArduPilot/ardupilot/pull/13760/commits/bea29c2929045b5cea9f4f72261665c7d552e524 was merged.
The remaining changes are limited in scope to the scheduling of rotor tilt during transition from VTOL to FW flight. During transition from VTOL to FW flight a tilt rotor quadplane would tilt rotors forward to the value set by Q_TILT_MAX and not allowed to tilt further until airspeed criteria had been met. However, depending on the combination of wing lift and pitching moment during transition, the tilting rotors could be throttled down, resulting in a slow acceleration and possibly a failure to achieve the required airspeed before time out occurred. Increasing Q_TILT_MAX can prevent this, but can also result in temporary loss of pitch control until airspeed has increased sufficiently for elevator to become effective.
The change in this PR results in the rotors being tilted to Q_TILT_MAX as per previous behaviour, but then continuing to tilt at the rate set by Q_TILT_FWD until throttle demand for any of the tilting rotors starts to saturate as the pitch controller increases the throttle of the titling motors to compensate for the reduction in vertical force. The rotors are then tilted back until the throttle saturation condition is removed and then tilted forward. This enables the pitch control requirements to be met with the maximum amount of forward thrust possible.
This requires that the throttle for titling rotors can be monitored - https://github.com/ArduPilot/ardupilot/commit/f68aed5c65c2c67bd147cc6b367b154608d8a9ac
The logic for the rotor tilt control during transition is implemented by https://github.com/ArduPilot/ardupilot/commit/f68aed5c65c2c67bd147cc6b367b154608d8a9ac
This has been tested on an Arace Griffin Pro. the following figure is from one transition test and shows how the forward rotors continue to tilt forward until the throttle clips. the rotors tilt back slightly, throttle un-saturates and the transition completion airspeed of 14 m/s is met shortly thereafter.
Altitude is not lost during transition
Here's an example of a transition for the same vehicle before the updates. Note how the rotors spend a significant time at Q_TILT_MAX with the front (tilting) rotor ESC demands below 1500 while the vehicle acceleration slows before the airspeed requirement is met.
What is Q_TILT_MAX for the example plots? That is to say at what tilt angle does the new behavior start?
Not really had a proper look through this yet. Just some first thoughts.
We already have some motor mixing in the tilt-rotor code that I really think should be in AP_Motors. This adds more stuff that is really mixing related. Maybe we could move it all to the motor library. I don't think there is any reason this code path is really transition specific, you might want to also use it when flying fast in VTOL modes with the new throttle handling.
exciting stuff
What is Q_TILT_MAX for the example plots? That is to say at what tilt angle does the new behavior start?
55 degrees
Not really had a proper look through this yet. Just some first thoughts.
We already have some motor mixing in the tilt-rotor code that I really think should be in AP_Motors. This adds more stuff that is really mixing related. Maybe we could move it all to the motor library. I don't think there is any reason this code path is really transition specific, you might want to also use it when flying fast in VTOL modes with the new throttle handling.
The method of winding up the limit if throttle clips will result in some interesting interaction with the position controller so I have kept he method transition specific at this time.
@IamPete1 Can we talk about your comment about moving this to the motor library. It's something I really don't want to do as the method used in this PR is currently only suitable for transition because of the slow rate the tilt winds forward and backwards based on motor saturation.
Edit: I've updated the description at the top of the PR to make the scope and rationale clearer. I agree that ideally we should be doing all tilt calculations in the motors library with the mixer having a 6DoF input vector (3 XYZ force and RPY torque). The mixer should also be able to take aerodynamic forces into account. That will be a big change.
we decided to add a new Q_TILT_OPTIONS parameter, AP_Int32, first bit will disable the new backoff behaviour also Q_TILT_RATE_FWD should default to 0, meaning use the current rate
@IamPete1 and @tridge The changes requested ended up being more extensive than I was anticipating, particularly with respect to use of the slew function. Can you please check what I have done is sensible. I'll check with @pompecukor if he is able to do a SITL test for us.
Adrian from Arace has done some SITL testing of this PR using a RealFlight tiltrotor model. The following shows the target tilt fraction new_tilt variable QTLT.NT, the current_tilt value after slew limiting (what is sent to the servo mixer) the maximum throttle fraction of the two tilting rotors QTLT.MT and the airspeed.
As expected the tilt continues forward until the maximum throttle reaches 95% after which the slew rate limited current_tilt is reduced to keep the max throttle at 95% and the vehicle continues to accelerate at the fastest possible rate. The target tilt fraction before rate limiting QTLT.NT rapidly switches with the duty cycle determining the rate limited slew value.
Height was maintained
The pitch response and PID data for the lift rotors and the elevator control show that pitch control was maintained despite the SITL model nose down trim bias during transition that loads the front tilting rotors.
@priseborough can we get some more love for this?
@tridge @IamPete1 I've rebased and will get some flight test logs from @pompecukor when he is able to.
@pompecukor was able to get a tilt-rotor flight test of this PR at commit https://github.com/ArduPilot/ardupilot/pull/25164/commits/49be71f9e2aa10971bda545972ec8203e98fc195
The VTOL to FW transition is working as expected. The forward tilt is briefly reversed, then resumed when the maximum throttle for tilting motors exceeds the 95% value.
The vehicle maintains roll and pitch control
Height is maintained and airspeed increases smoothly
There have been a couple of tiltrotor changes recently (https://github.com/ArduPilot/ardupilot/pull/26979 https://github.com/ArduPilot/ardupilot/pull/26978), so I think it would be worth a rebase to make sure its not broken by those changes.
@IamPete1 It rebased cleanly.
@priseborough @IamPete1 What is the hold up on this one? Anything we can help with?
@IamPete1 Ping