We have a handful of FireFLY6 kits that we’ve been using as training and testing aircraft, and lately I’ve been working on dialing them in a bit better and testing out 4.5 in the meantime.
Today, I had several failed attempts at transition, despite not having that issue previously. I recently performed a TECS tune, so I suspected this had something to do with my THR_MAX
, which I had just recently reduced (without this, I’d need to crank the climb rate and pitch up to levels that I’d rather not). I also recently set bit-1 of FLIGHT_OPTIONS
to make stick-center the cruise speed (so previously, when I would transition to forward-flight, I’d be commanding 17.5m/s, but now I’m commanding 15m/s).
Logs: FF6 Failed Transitions - Google Drive
When I reverted THR_MAX
alone to 100%, I still couldn’t get to airspeed min. And when I tried commanding 22m/s during transition with THR_MAX
set to 70% I couldn’t quite get there either (it actually finished the transition right before I gave up and switched to QHover, but it shouldn’t have taken that long). Only setting THR_MAX
to 100% and putting the stick up to command a high airspeed on transition could I get above airspeed min and complete the transition.
When analyzing the logs, I’m noticing something strange. My transition axle isn’t going to the Q_TILT_MAX
of 45 degrees, it’s going to 25 degrees. It’s also backing off even more as I get near min airspeed. Looking at the code, I think I see the culprit: https://github.com/ArduPilot/ardupilot/blob/ab68066e9c7a671b6a032289d5eda382b3d3245b/ArduPlane/tiltrotor.cpp#L328
When you are above 50% throttle, it’s supposed to go to Q_TILT_MAX
, but really, it’s when you are 50 percentage-points above throttle min. So my real issue was that I also recently cranked THR_MIN
all the way up to 43% (yes, the FF6 is very draggy; again, I could just turn the climb/sink and pitch limits larger, but I want to keep it to something in the reasonable 3m/s range up/down, which 40%-70% throttle covers nicely). So, in my case, it won’t go to Q_TILT_MAX
until the throttle out reaches 93%.
Should this line be changed so that it checks if you are more than halfway between min and max, instead of 50 points above min? Or should it just be checking that you are more than 50 points above 0? Should it just be if you are above trim throttle (this actually seems reasonable to me)? Am I just being a weirdo for using a non-zero THR_MIN
, and a less-than-100 THR_MAX
?