My Tilt Mixer does not work properly anymore since V1.9.X

Can the V19_VT_ROLLDIR=0 error be suppressed ?
As soon as it is set to 0 the servo mixer outs change to wrong values although there is no roll as source used.

with V19_VT_ROLLDIR=1 the mixer still seems to work as expected like in V1.8.2
Out no 4 is currently in use for an external X-Fade mixer

E-flite Convergence Tricopter Y-Configuration Mixer

Motors

R: 3y 10000 10000 10000 0

XFade Source (AUX1/RC7) MC=2000 FW=1000

M: 1
O: 10000 10000 0 -10000 10000
S: 3 5 0 -19888 9808 -10000 10000

Tilt mechanism servo mixer + (AUX3/RC12) later (FW Roll)
#RIGHT up:1985 down:1030 Limit:650-2450
M: 3
O: 10000 10000 0 -10000 10000
S: 1 4 1000 -10610 4840 -10000 10000
S: 0 2 4444 4444 0 -10000 10000
S: 3 7 -5850 -5850 0 -10000 10000

#LEFT up:1030 down:2015 Limit:650-2450 Center=1550
M: 3
O: 10000 10000 0 -10000 10000
S: 1 4 1000 10940 -5770 -10000 10000
S: 0 2 4444 4444 0 -10000 10000
S: 3 7 5850 5850 0 -10000 10000

V19_VT_ROLLDIR=1
device: /dev/pwm_output0
channel 1: 900 us (alternative rate: 400 Hz failsafe: 0, disarmed: 900 us, min: 1118 us, max: 1943 us, trim: 0.00)
channel 2: 900 us (alternative rate: 400 Hz failsafe: 0, disarmed: 900 us, min: 1118 us, max: 1943 us, trim: 0.00)
channel 3: 900 us (alternative rate: 400 Hz failsafe: 0, disarmed: 900 us, min: 1118 us, max: 1943 us, trim: 0.00)
channel 4: 2000 us (alternative rate: 400 Hz failsafe: 1925, disarmed: 1925 us, min: 976 us, max: 2011 us, trim: 0.00)
channel 5: 1985 us (default rate: 50 Hz failsafe: 1985, disarmed: 0 us, min: 650 us, max: 2450 us, trim: 0.00)
channel 6: 1030 us (default rate: 50 Hz failsafe: 1030, disarmed: 0 us, min: 650 us, max: 2450 us, trim: 0.00)

V19_VT_ROLLDIR=0
device: /dev/pwm_output0
channel 1: 900 us (alternative rate: 400 Hz failsafe: 0, disarmed: 900 us, min: 1118 us, max: 1943 us, trim: 0.00)
channel 2: 900 us (alternative rate: 400 Hz failsafe: 0, disarmed: 900 us, min: 1118 us, max: 1943 us, trim: 0.00)
channel 3: 900 us (alternative rate: 400 Hz failsafe: 0, disarmed: 900 us, min: 1118 us, max: 1943 us, trim: 0.00)
channel 4: 2000 us (alternative rate: 400 Hz failsafe: 1925, disarmed: 1925 us, min: 976 us, max: 2011 us, trim: 0.00)
channel 5: 2011 us (default rate: 50 Hz failsafe: 1985, disarmed: 0 us, min: 650 us, max: 2450 us, trim: 0.00)
channel 6: 1056 us (default rate: 50 Hz failsafe: 1030, disarmed: 0 us, min: 650 us, max: 2450 us, trim: 0.00)

Let me mention @sfuhrer and @tumbili here to help.

@jlecoeur Mind having a look? If not I could probably help out just wondering if you are more efficient as you implemented the switch.

Hi @taileron,

I need more information to help you.

If you do not use FW roll as control input, how do you control roll when in fixed wing mode ? Can you send a picture of your drone ? In any case, as FW roll is not used in your mixer, you should be able to safely set V19_VT_ROLLDIR to 0.

Can you describe what exactly is wrong with your mixer when V19_VT_ROLLDIR=0 ? I am surprised that it works as in v1.8.2 when V19_VT_ROLLDIR=1, because the multirotor and fixed-wing controls are not mixed until the param is set to 0 (see https://github.com/PX4/Firmware/blob/b7d0b4511c131582e232fb9a2809851bb41ec4fe/src/modules/vtol_att_control/vtol_att_control_main.cpp#L671-L703)

To test my mixer I first start to check the neutral positions of the corresponding servo outs.
As soon as the actuators are enabled V19_**DIR=0 there is no neutral position anymore. Only when the Plane is aligned nose pointing north direction, yaw out gets a neutral position.
So the mixer behaves absolutely right. ItĀ“s only the yaw PID controller that doesnĀ“t match to my purposes anymore.
For fw IĀ“m using X-fade mixers contolled by output 4 to do the mc -> fw transition with a tx fader fw is controlled by a second fc.
The problem would be now, while flying around with the second controller PX 4 in acro mode while back transition to fw (both flight-controllers stabilized mode) yaw immediately wants to go to the previous stored stabilized heading.
V1.8.2 starts with neutral yaw position and neutralises the position by activating acro even for a short moment.
Important would be a posibility to kill all cumulated (stabilized mode) yaw I term before switching from acro to stabilized.

ā€¦ sorry I forgot to mention: this plane uses a Pixracer with only 6 outputs:1,2,3 = Motors, 4 = X-fade source, 5,6 = tilt / yaw / (vec trst)
A second fc provides signals to the elevons (elevator/aileron) and vectored thrust function to the yaw tilt control servos in fw mode.
I tried to integrate vectored thrust into fw acro of PX4 but couldnĀ“t achieve this yet.
Found no way to mix roll/nick only in fw mode into the two tilt servos.
Currently most of my transitions to mc are done via moments of gliding (motors tilt up to reduce drag) without any yaw control. At the end of the gliding periods throttle has to be started again in this moment yaw control should be set to a neutral position when yaw control kicks in, otherwise the plane would fly a crazy twist of death ā€¦

Ok, this is not a mixer problem then.

Can you summarize your issue in a short sentence ? Two logs in v1.8 and v1.9 to demonstrate what is different would help.

There are two logs with 1.8.2
https://review.px4.io/plot_app?log=2998bcc2-07c2-4af6-821c-627187f0d79c
includes a bit of aerodynamics and at 4:20 a moment of gliding
https://review.px4.io/plot_app?log=58e1cc94-533b-4737-ac84-4a1e685dc163
mission and tilt mixer test (aux3 passthrough) mixed to yaw/tilt, trying to hold pitch axis in a horizontal position for flying mc forward/backward, allows flying in strong winds.
In position and mission mode it can be used to adjust the pitch angle of the plane e.g. to point the camera view up and down.
with 1.9.1 I have done only mc flight tests yet starting with nose pointing north and I gonna try to simulate the fw flight by holding the aircraft tight with my hand later.

OK, please ping me when you have a log

https://review.px4.io/plot_app?log=94c6705a-3114-4609-91ec-4b1e6ebbd5a6
hand hold test
https://review.px4.io/plot_app?log=1390fa06-7f58-4c51-8c5f-8dd4fba3013b
mc flight

the problem is not easy to see cause the log currently starts with the arming procedure.
yaw position is far left position (servo pushes to its limit) only after arming it takes a more neutral position but with disarm it immediately returns to the far left limit.

Only when the plane is pointing north the servo is enough away from itĀ“s limit

further issues appeared:
pwm min -c 123 -p 1118 in extras.txt and the min throttle settings of 1118 donĀ“t apply anymore the motor outputs always deliver 1000uS in mc mode instead of 1118
The escs are idle at 1118 to be able to glide and have immediately full control short above hitting the ground.
And even with airmode disabled and zero throttle pid activates the motors. That disturbs gliding with motors tilt up.
Probably I have to go back to 1.8.2 cause these are too special problems coming with 1.9.X.
My final goal still is to bring vectored thrust into the px4 mixer without the need of external processing hardware and integrating my spare Pix-Falcon to a Mini Convergence

for me especially one really important feature seems to be missing in V1.8.2
IĀ“m using Spektrum SRXL receivers (SPM4649T)
Is there a way to enable srxl rssi readout (that works really great in v1.9.1) in V 1.8.2 as well?

On the logs you sent, it looks like you have not set the parameters PWM_MAIN_DISx (or PWM_AUX_DISx). Set it to a neutral position for the yaw servos (something around 1500) and they will not go to the far left position when disarmed.

for me that should be settled by an extras.txt entry: pwm disarmed -c 5 -p 1500 but even that doesnĀ“t apply anymore since V1.9.X
Without forcing outputs to predefined fixed values, up to V1.8.2 if the vehicle shows proper neutral positions that was an easy way to check if all my mixers loaded correctly, before I arm the vehicle.

Have you set the PWM_MAIN_DIS parameter?

In former times this behaviour was the best indicator, that a mixer was not loaded.
-> still the same behaviour (1ā€¦3=motors 4=x-fade 5,6=yaw/tilt-servos):
pwm info
device: /dev/pwm_output0
channel 1: 900 us (alternative rate: 400 Hz failsafe: 0, disarmed: 900 us, min: 1118 us, max: 1943 us, trim: 0.00)
channel 2: 900 us (alternative rate: 400 Hz failsafe: 0, disarmed: 900 us, min: 1118 us, max: 1943 us, trim: 0.00)
channel 3: 900 us (alternative rate: 400 Hz failsafe: 0, disarmed: 900 us, min: 1118 us, max: 1943 us, trim: 0.00)
channel 4: 2000 us (alternative rate: 400 Hz failsafe: 1925, disarmed: 1925 us, min: 976 us, max: 2011 us, trim: 0.00)
channel 5: 2032 us (default rate: 50 Hz failsafe: 1500, disarmed: 1500 us, min: 650 us, max: 2450 us, trim: 0.00)
channel 6: 1077 us (default rate: 50 Hz failsafe: 1500, disarmed: 1500 us, min: 650 us, max: 2450 us, trim: 0.00)

but the values are still directly coupled with the absolute direction the vehicle is momentary pointing to, if it is straight nose to north, the pwm values are going very close to neutral !!!

I am sorry but I still do not understand what your problem is. Please give instructions to replicate your issue, and please send logs on v1. 8 and v1. 9 where you follow these same instructions.

@tumbili FYI, this is not related to the VTOL roll change that I implemented. It looks like something happens when disarmed that did not happen in v1. 8

it seem that it concerns only the current behaviour of yaw pid controller.
It isnĀ“t mixer related. IĀ“ve downgraded to 1.8.2 on the vehicle.
IĀ“m still tying 1.9.X and master on currently spare PixFalcon and PixRacer.
For tests IĀ“ll break down the mixer to output only yaw directly to one output to see what really happens and to be able to use standard precompiled firmware files to avoid issues probably caused by the ā€œmakeā€ procedure. (for the vehicle an extended pwm limit of 2500uS is needed, even that could cause the fault)

itĀ“s only the behavior of the 1.9.X yaw.
IĀ“ve flashed 1.9.2 release and changed the mixers to yaw as only source (limits 900/2100 so output should be always 1500).
The yaw output is always directly coupled to the vehicles direction yaw should be decoupled if its not armed !!

@taileron, do you have a safety switch on your drone? Or have you disabled it (CBRK_IO_SAFETY)?