Dual-motor tailsitters

It’s great to hear that the throttle/tilt-based gain scaling worked well since airspeed sensors are often inaccurate, and pitot tubes are fragile. Many thanks for the logs, the one for gain attenuation shows that the scaler correlates well to actual airspeed and that yaw (body roll) and pitch oscillation amplitudes are quite low:

BTW, I tried bodyframe roll in plane-mode with the Dart myself, and was unable to hover it in wind, even though I had practiced in RF8 and thought I was reasonably good at it. I switched to the new MC mode bodyframe roll, and was able to fly around a bit and land OK. I guess reflexes take over when you’re flying the real thing :slight_smile: The new mode is Q_TAILSIT_INPUT_TYPE=2 in the flight-test-hybrid binaries. Input_type 3 is for plane-type controls with bodyframe roll. I suppose if you were expert in QACRO, you would want type 3 to keep the same controls in QHOVER.

Also, I’m working on a PR to update the wiki for tailsitters: https://github.com/ArduPilot/ardupilot_wiki/pull/1671/files
I’d appreciate it if you could check it for clarity and errors/omissions.

Hi Guys,
I need you input about what happened to my vectored tailsitter.

My Vectored Tailsitter have bad oscillation on the motor servos. sometimes on right motor servo sometime on the left motor servo. this oscillation often occur on right motor servo.
i’m trying to change the Q_A_RAT_PIT_P and Q_A_RAT_PIT_D, no changes, the oscillation still there.
Trying to change the Q_TAILSIT_THSCMX from 1 to 5 , it is still there.
Trying to do some autotune on pitch axis, well this cannot be done caused by oscillation.

Here is my log :
https://drive.google.com/open?id=1WqhFMX1DK0OoODVaAFFILCxTSb-tV3Eu

and here is the video :

@Hadits_Baroya
Oscillations can be seen with servo1, 2, 6 and 7 which are elevon L/R and tilt motor R/L, so for me oscillations are not only with tilt motors. One thing weird is the neutral position of servo 6 and 7 respectively around 1900 and 900.
If you want to reduce only the gain of tilt motor servos you can reduce Q_tailsit_vhgain.
But probably q_a_rat_pit_p needs to be reduced. Q_a_rat_rll_p seems to be too high too.
You can set q_tailsit_thscmx=1
Your video does not work, it would be better to have one.

Just to understand, what is the meaning of CTHPXXX and where they can be found in the log ?
Yes, the first version of body frame roll was really hard to fly because it requires to face first the whished direction and is even harder when the wing is tumbled by the wind. I will try the new body frame roll this WE and will read the PR talsitter wiki this WE too.

The CTHP log record is a debug feature in the tailsitter gain scaling code. It contains highpass filtered gyro rates (and a mean-square measure of each) along with the gain scale value at 100Hz sample rate:

AP::logger().Write("CTHP", "TimeUS,MSQr,MSQp,MSQy,HPr,HPp,HPy,Scl,ASpd", "Qfffffffb",

The highpass values are HPr,HPp,HPy and the scale factor is Scl. Airspeed (ASpd) is included for comparison. The MSQr/p/y values are recorded for design of a (potential) automatic method to detect and cancel oscillation.

Thank you for your input.

Yes, the neutral position of servo 6 and 7 are 1900 and 900, maybe I have to trim it manually again to get 1500 for neutral position.

I will try to play with the Q_tailsit_vhgain and give a report back.

thank you so much.

The most tricky part to understand is about parameters controlling rates and limits (the note line 142), not only because the note contains a lot of important information but also because q_yaw_rate_max does not have the same meaning with respect to plane frame in stabilized or acro modes. I made two more flights in my garden this afternoon to verify one more time and your descriptions are correct.
Descriptions concerning q_tailsit_input, qacro and gains scaling are OK too and no omissions.

Thanks for the review and comments. I’ll try to fix the issue with misusing parameters and add new ones if necessary to make setup more straightforward.

I have just got round to looking at this, quite hard to see anything clear. If your seeing oscillation at higher airspeeds you need to reduce q_tailsit_spdmax even further setting Q_tailsit_spdmin to zero will probably also help.

Qacro at high speed with this method is essentially the same as normal acro so it should be roughly the same feel as that.

Not sure if is a methodology issue or just that it needs more time to get the parameters worked out. Hard to tell how acurate the airspeed sensor is from just the vid.

I think now the weather is beginning to improve I will have to build one to test with myself.

Yes, spring is already there and glad to hear you are going to build a test wing.

My airspeed was not accurate, it used to be but not with the last flights, I found I have leaks on the pitot, I have to fix that and make more tests.

I am still testing binaries from post 1648 and I think I found a bug

During the first part of the forward transition motors output is driven by the throttle stick position and not by q_m_thst_hover as it used to be. This is dangerous because the wing eventually stall.
If needed I have the flight log with numerous transitions but the one above is the most representative because I had the reflex to increase the throttle.

I can’t find any recent code changes which would have changed the throttle behavior on forward transitions. Do you have a log which shows the old behavior? That would tell me which version of code to compare to.

This is a list of binaries and my comments about forward transition (I have checked log)

post 1488 pr-quad-ts : log post 1521 transition OK
post 1536 : not tested
post 1542 quad tailsitter code pr10336 : log post 1555 transition OK
post 1554 : not tested
post 1572 torque yaw fix pr10334 : log post 1582 transition OK
post 1606 pr10401 : log post 1608 and 1610 transition OK
post 1611 qacro : I have one log but no transition tested
post 1614 qacro : I have 6 log but no transition tested
post 1630 pr-add-qacro : log post 1634 but no transition tested, 9 other log and only one transition that seems OK.
Post 1630 pr_body_frame yaw : not tested
post 1648 gain interpolation : transition problem.
post 1659 flight test hybrid : not tested

Before qacro there was no transition problem.
Since qacro (1611 to 1630) I have almost not tested transition so I can’t say. But I still have the binaries so I can check.
I have several logs with forward transition depending on the throttle stick position since binaries post 1648

Best log to see the old behavior are log44 post 1582 and logPR10401-2 post 1608

@losawing Thanks, that was what I needed to find the change involved.
I’ll work with @iampete to resolve the issue.

Brief demo with Q_TAILSIT_INPUT = 2 (BF_ROLL_M)
using the flight-test-hybrid-rebased binary…

roll stick control axis rotates from multicopter X to multicopter Z (tailsitter X) as nose pitches down from zenith toward the horizon

1 Like

I am finally catching up :sunglasses:
I made 2 flights this evening with flight test hybrid binaries with tailsit input=3 and angle max=8000
This is a good mode to fly q_hover, very intuitive, comparable to qacro with the help of the stabilization when sticks are released. A very important parameter is q_tailsit_rll_mx, must be >70 otherwise the wing bank but does not turn.

The forward transition is also linked to throttle stick. Tomorrow I will test again pr_add_qacro to see the transition behavior.

is this all forward transitions or only from Qacro? cant see any changes to the code that would cause this, maybe something more complicated is going on.

@iampete I sent you a message on the gitter channel about that. Are you on Skype?

no, also from q_hover

I just rebuilt the flight-test-hybrid-rebased binaries with a temporary fix that should restore the original forward transition behavior.