Differential Thrust Troubleshooting FF6
The FireFLY6, a continuous tilt Y6F platform, has unusual issues with controlling yaw during transition. Unlike vectored platforms, the hover yaw authority is limited to motor speed differentials, and as the transition axle turns down, the authority quickly falls off in favor of differential thrust in fixed-wing flight.
Tilt transitions consist of 3 states
- AIRSPEED WAIT - Turn down at Q_TILT_RATE_DN until Q_TILT_MAX and wait for airspeed
- TRANSITION_TIMER - Turn at Q_TILT_RATE_DN until fully rotated down while mixing hover and plane throttle
- TRASNITION_DONE completed transition
Starting with an older winglet setup, we were able to tune the yaw damper and test with smaller and smaller winglets. This went well, and the aircraft reached a point where sharp turns and rudder commands were not able to create a flat spin.
At this point we encountered issues with our hover filters and the inability to transition due to the small TECS throttle window/tilt map.
The hover filters needed tweaking with each winglet change, as the winglets were heavy enough at the end of the wings to change the frame resonance and cause instability. This was fixed with a few autotunes.
Once able to transition more consistently we encountered large sideslip angles in transition resulting in some stalls/flatspins.
Initially we pointed at the lack of yawtarget in transition for continuous tilt therefore we added a Q_OPTION to enable the yawtarget. This seemed to have no change on our transition problems.
ArduPlane: Add Q_Option for tilt yaw control in transition · ClayFG/ardupilot@ce2ec32
add yaw control for tiltrotor in TRANSITION_TIMER state · ClayFG/ardupilot@594072e
This Is the a plot of a successful transition at this point. There are a lot of fields but I beleive they are all important to get a good picture of what the transitions looked like. Sideslip angle (RED) is nonzero during transition but is under control until about 60 degrees of transition axle (PURPLE)
Another transition from the same flight where the plane flipped when too much attitude error accrued. It recovered in qsabilize.
Here we isolated that in all transitions everything is under control until we reach transition airspeed and the TRANSITION_TIMER state happens. Throttle would consistently climb to max overshooting airspeed and have a sharp falloff in control authority quickly stalling unless transition fully completes first.
This seemed like some sort of issue with the mix initially and found other people mentioning odd throttle behavior in tilt transitions.
Tilt-Rotor VTOL Transition Throttle Behavior - ArduPlane / VTOL Plane - ArduPilot Discourse
Throttle Anomaly with Tilt-Tri-VTOL Transition - ArduPlane / Plane 4.5 - ArduPilot Discourse
but assume the problem is more bound to our issues with attitude control and the throttle being necessary.
we did test the mixer adding logging for the QTUN and CTUN throttle and observed the throttle output scaling between the two with angle.
The next Idea was to slow or speed up the transition to give time for integrators to build or attempt to ‘skip’ the uncontrollable part of our transition.
Slow showed no improvements and every time we reached ~60 degrees on the transition axle things quickly lost control.
Through many of the logs we looked at the motors outputs to comprehend when the plane was trying to use hover throttle to control yaw vs differential thrust and it always looks extremely messy and out of control at these high angles.
at 60 degrees the quadcopter yaw control will have half of its normal effectiveness in the yaw axis and .86 of its normal yaw authority in the roll axis. at the same time our differential thrust has .86 in yaw authority but also .5 in roll authority. During all of this we often have saturated motors and elevons at max deflection.
Fast was usable but not pretty. With the strong plane an hover tunes we were able to safely turn the transition rate to 120deg/s for consistent transitions which looked great in the TRANSITION_TIMER state but dropped 25 feet in the initial snap to 45 degrees while waiting for airspeed.
120degrees per second Q_TILT_RATE_DN
90degrees per second Q_TILT_RATE_DN
This was functional but not pretty and control authority still struggled in the beginning of transition.
Adding a new parameter to control initial and final transition axle speeds has solved our problems since keeping our slow AIRSPEED_WAIT Q_TILT_RATE_DN and speeding up our final to ~120 where there is no time to accumulate large sideslip angles
Added dual tilt rate functionality for down transitions · ClayFG/ardupilot@c3161de
Auto flights -transitions still seem a bit aggressive in auto
Here is a transition from one of the most recent flights
This transition has a slow initial Q_TILT_RATE_DN of 15 and Q_TILT_RAT_DN_FN of 120
The initial sideslip angle came from drifting in QHOVER not quite head to wind as seen here with the flight path. It seems to settle out with airspeed.
From this testing PR#27194 appears to work well and I intend on polishing the other changes mainly the option to have a second parameter controlling the tilt speed in TRANSITION_TIMER and opening a PR in the near future.