Custom mixer not working

Hi,

I am trying to build a custom VTOL airframe along with which I have written a custom main mixer file. I am unable to get any pwm output by using my mixer. My observations are as follows:

  1. If I ditch my custom mixer, and use a simple multicopter mixer instead, everything seems to work fine
  2. As soon as I start using my custom mixer, things become problematic. I connected an oscilloscope to the main 1 pin. I observed that I am getting regular PWM output when the safety switch is off, but as soon as I press the safety switch, the PWM output drops to 0 and becomes a flat line (i.e., mixer not working)
  3. I checked the bootlog.txt on the SD card and it shows the following error
    PX4IO CRC OK after updating
    PX4IO CRC OK after updating
    ERROR [init] Failed loading mixer: /etc/mixers/custom_mixer.main.mix
    ERROR [init] Failed loading mixer: /etc/mixers/custom_mixer.main.mix
    ERROR [init] Failed loading mixer: /etc/mixers/custom_mixer.main.mix

Here is the mixer I wrote for my main 1 output

Main 1

6 scalers total (multirotor - roll, pitch, yaw, throttle; fixed wing - yaw, throttle).

M: 6
O: 10000 10000 0 -10000 10000
S: 0 0 6500 6500 0 -10000 10000
S: 0 1 6500 6500 0 -10000 10000
S: 0 2 6500 6500 0 -10000 10000
S: 0 3 0 20000 -10000 -10000 10000
S: 1 2 6500 6500 0 -10000 10000
S: 1 3 0 20000 -10000 -10000 10000

Can someone help understand why this is not working? Thank you!

This may be way off what youā€™re problem is, but Iā€™ve also come across erratic behavior when making custom or large mixers (which it seems yours might be?). There is a limited memory given to the mixer file, so if you make a mixer that exceeds that limit it may behave strangely. This is where it is:

line 42: #define PX4IO_MAX_MIXER_LENGHT 230

Possibly by increasing this number you might get a larger mixer working, but I havenā€™t tried it myself so no guarantee (Iā€™ve asked around but havenā€™t heard back whether it would work).

Good luck with it!

@juxtwo Thanks a lot! This helped, I can now run my own mixer.

Facing a new problem now. For my VTOL, can I have different mixers for multicopter and FW? Currently I have programmed my multicopter mixer on control group 0 and FW on control group 1, but for some reason I am seeing interference from control group 1 mixer when I am flying multicopter.

haha yes I had the exact same problem!!! The issue is with tiltrotor.cpp, in lines 383-416. there is no separation between actuator control group 0 and control group 1. There is a weighting factor that means that in forward flight there is no MC actuation. But this weighting factor is not applied to FW actuators, which means that both MC and FW actuators are use in MC flight. Make sense?

To fix this you need to multiply the FW actuators by (1- _mc_roll_weight) so that in MC mode theyā€™re turned off. What type of vehicle is it for?

Hereā€™s the code

void Tiltrotor::fill_actuator_outputs()
{
_actuators_out_0->timestamp = _actuators_mc_in->timestamp;
_actuators_out_0->control[actuator_controls_s::INDEX_ROLL] = _actuators_mc_in->control[actuator_controls_s::INDEX_ROLL]
* _mc_roll_weight;
_actuators_out_0->control[actuator_controls_s::INDEX_PITCH] =
_actuators_mc_in->control[actuator_controls_s::INDEX_PITCH] * _mc_pitch_weight;
_actuators_out_0->control[actuator_controls_s::INDEX_YAW] = _actuators_mc_in->control[actuator_controls_s::INDEX_YAW] *
_mc_yaw_weight;

if (_vtol_schedule.flight_mode == FW_MODE) {
	_actuators_out_0->control[actuator_controls_s::INDEX_THROTTLE] =
		_actuators_fw_in->control[actuator_controls_s::INDEX_THROTTLE];

	/* allow differential thrust if enabled */
	if (_params_tiltrotor.diff_thrust == 1) {
		_actuators_out_0->control[actuator_controls_s::INDEX_ROLL] =
			_actuators_fw_in->control[actuator_controls_s::INDEX_YAW] * _params_tiltrotor.diff_thrust_scale;
	}

} else {
	_actuators_out_0->control[actuator_controls_s::INDEX_THROTTLE] =
		_actuators_mc_in->control[actuator_controls_s::INDEX_THROTTLE];
}

_actuators_out_1->timestamp = _actuators_fw_in->timestamp;
_actuators_out_1->control[actuator_controls_s::INDEX_ROLL] =
	-_actuators_fw_in->control[actuator_controls_s::INDEX_ROLL];
_actuators_out_1->control[actuator_controls_s::INDEX_PITCH] =
	(_actuators_fw_in->control[actuator_controls_s::INDEX_PITCH]);
_actuators_out_1->control[actuator_controls_s::INDEX_YAW] =
	_actuators_fw_in->control[actuator_controls_s::INDEX_YAW];	// yaw
_actuators_out_1->control[4] = _tilt_control;

}

@juxtwo Seems like we are facing similar issues :slight_smile: Maybe you already know what I will face next :slight_smile:

I am trying to understand what you described. Is this the correct way to do it?

_actuators_out_1->timestamp = _actuators_fw_in->timestamp;
_actuators_out_1->control[actuator_controls_s::INDEX_ROLL] =
-_actuators_fw_in->control[actuator_controls_s::INDEX_ROLL] * (1 - _mc_roll_weight);
_actuators_out_1->control[actuator_controls_s::INDEX_PITCH] =
(_actuators_fw_in->control[actuator_controls_s::INDEX_PITCH]) * (1 - _mc_pitch_weight);
_actuators_out_1->control[actuator_controls_s::INDEX_YAW] =
_actuators_fw_in->control[actuator_controls_s::INDEX_YAW] * (1 - _mc_yaw_weight); // yaw
_actuators_out_1->control[4] = _tilt_control;

I am building a project with a 8 motor tiltrotor design. If all goes per plan I will post a video of maiden flight within this month :slight_smile:

@juxtwo Good new, this works! You are a lifesaver. I am able to have only MC in MC mode now. Now I come back with new challenges

  1. The PIDs dont show any response in FW mode i.e., not seeing any feedback when I move the pixhawk in FW mode. All working as expected in MC though. Are there separate PID parameters for FW in VTOL settings?

  2. I am using a simplified mixer now

R: 8x 10000 10000 10000 0

Main 1

6 scalers total (multirotor roll, pitch, yaw, throttle fixed wing yaw, throttle)

M: 2
O: 10000 10000 0 -10000 10000
S: 1 2 -6500 -6500 0 -10000 10000
S: 1 3 0 20000 -10000 -10000 10000

I then have similar mixers for the rest of my 7 motors.
Here I have defined Yaw in FW mode for each of my 8 motors but see no response. Very weird

  1. In the axillary mixer I have defined a scalar on control group 3 for all my servos as
    S: 3 5 600 600 -600 -10000 10000
    I am only able to access this in FW and not in MC mode. I need this in MC mode to allow the servos to tilt to give me forward drift instead of pitching the craft forward.

  2. When transitioning back from MC to FW, I observe that all my motors slow down dramatically. This is scary as the craft will drop dead from the sky. I am using param set VT_B_TRANS_THR 1.0 but still this happens. Again weird behavior.

Any help or insight would be great!

Great to hear! Yeah there are a lot of issues with tiltrotor.cpp, I think it was made with a particular airframe in mind and not the general case, so if you do anything slightly custom you get all sorts of strange/volatile behavior. Looks like youā€™ve already come across at least one of those strange behaviors but here are the main ones:

1- MC yaw weight goes instantly to 0 after 7m/s (hardcoded). Can result in sudden yaw/roll changes depending on the state of transition

2- FW throttle only applied in FW mode. Means that in a mission, your aircraft wonā€™t accelerate into the correct transition speed because itā€™s only reading MC throttle inputs

3- In the back transition the throttle is commanded to cut to 0! (Thatā€™s what you saw!). This to prevent sudden thrust inputs in strange directions (Iā€™ve crashed an aircraft when I changed it). But like you said it leads to the aircraft losing a lot of altitude, and isnā€™t great if you suddenly need to get back into hover mode (nearly crashed an aircraft because of that)

4- Again in the back transition, the MC weighting is set at 0 throughout. When I first edited the back transition I only removed the throttle cut line, but left this line. If this line is kept unchanged and the throttle line is removed (so you can have a powered back transition) you get a horrible mix of MC commands when the aircraft is not ready for MC flight (so MC roll = FW yaw with diff thrust, therefore input =/= output, autpilot canā€™t control the aircraft). Long story short, if you want a powered transition youā€™ll need to progressively change the MC/FW weighting according to how far through the transition it is. Iā€™ve never tested this in flight so I canā€™t guarantee it will work.

5- If you transition to FW mode while in MANUAL flight mode, the aircraft appears to lose ALL control! Iā€™ve lost an aircraft to this, nosed dived from 50m, not good! I donā€™t know why this is the case (itā€™s somewhere else in the firmware), or if this happens every time, but you want to make sure youā€™re in STABILIZED mode before taking off. Unfortunately, regardless of what youā€™ve set for your flight modes, your aircraft will ALWAYS start in MANUAL mode. To fix this, make sure ā€œPERMANENT STABILIZATIONā€ is ENABLED. It seems to have worked me for the time being.

Iā€™ve nearly finished making an improved tiltrotor.cpp which should work better for all tiltrotor/tiltwing aircraft (includes fixes for the above problems related to the code), but I havenā€™t worked out how to upload it to github yet. Iā€™ll let you know when I do, we might even be able to get multiple groups working on it so itā€™s optimized for different scenarios.

As to your question, Iā€™m not quite sure myself either, a couple of thoughts though:
Issue #1 - Best guess is itā€™s due to issue #5 I mentioned above, if in manual mode it might just be cutting all control (but it seems that you get roll and pitch control?)
Issue #2 - Could be something with the yaw scaling/weighting. making sure the logic is correct so that the actuator output is correctly applying yaw in FW mode
Issue #3 - Sounds like youā€™re using servos for tilt and pitch (/forward movement) in MC mode? Iā€™d use a ā€œS: 1 4 ā€¦ā€ command for the tilt control, and ā€œS: 0 1 ā€¦ā€ for MC pitch. If you donā€™t want the aircraft to pitch forward in MC mode, set your motor command line such that there is no pitch control using thrust, ei:

R: 8x 10000 0 10000 0

Then, in QGroundControl, you may want to change the parameter that limits pitch angle to something small (<10deg). I tried this a while ago and found I lost all pitch command control, but I hadnā€™t learnt I could stop my motors from applying pitch commands.

That said, if you work out a way to do it with another strategy Iā€™m keen to give it a shot!

@juxtwo You seem to be the guru on this :slight_smile:

Can you share your tiltrotor file with me while you figure the github upload? A PM or email (vishusinghal2000@gmail.com)? Would be very helpful to leverage all the heavylifting you have done already.

Also figured another solution to the forward drift in MC problem.
I want the pitch to be controlled my motor speed (so the PIDs can do their job) while I want forward lateral movement with the tilting of servos.
I left the multirotor command as is. I changed the code in my aux mixer a little bit to

S: 3 5 600 600 600 -10000 10000

and this works seamlessly. Give it a shot :slight_smile:

Sorry to highjack this post. but @vissin can you share your tilt-rotor frame? Iā€™m also working on a tilt-quadrotor (4 motors + 4 servos) so I think many of our work is coincident and we can help eachother mutually. Iā€™ve already messaged @juxtwo about some other issues, so we have here a very focused trio.

Any of you in the PX4 slack? Would love to ask you some questions on a more chat format.

Cheers

@RicardoM17 Glad you joined us, the more the merrier :slight_smile:
I am building a tilt-octa (8 motors and 8 servos)
And I also just joined slack

1 Like

I am also developing a custom tiltrotor. I donā€™t understand how the mixer file allows one to add a main 1 group after the R: 8x line without it interpreting it as an additional actuator. I see the convergence file has all the rotor actuators specified with an R: line and then plunges straight into the elevons. Can you help me by explaining and/or share your mixer file?

@malcolm What is the issue? You say ā€œI donā€™t understand how the mixer file allows one to add a main 1 group after the R: 8x line without it interpreting it as an additional actuator.ā€ Well it doesnā€™t. It interprets it as an additional actuator.

Convergence Mixer: https://github.com/PX4/Firmware/blob/master/ROMFS/px4fmu_common/mixers/vtol_convergence.main.mix

Convergence description: https://docs.px4.io/en/frames_vtol/vtol_tiltrotor_eflite_convergence_pixfalcon.html

The R: line maps the 3 motors, then thereā€™s a Z: line because MAIN 4 is empty. Afterwards each M: maps to a MAIN input from 5 - 8.

If you share more info about your frame/mixer file I can help. @ me here or find me on the PX4 slack

Its a hexacopter + with a single tilting rotor (No 1), the front. In the post that vissin shared on Mar 17 he shows a line with R:8x and then a separate stanza for Main1. How does this work? How does the mixer file define an extra stanza for a motor that was already specified in the R: line?

@malcolm his post is quite confusing but I donā€™t think he is doing what you say. or at least I think it shouldnā€™t work.

You can use a R: line and then add mixers for the remaining motors. If you want to add something to the mixer of one of the motors already in the R: line then I donā€™t think you can do this afterwards.

But in your cause you can simply add a custom mixer with 7 M: lines (one for each of the 6 motors + 1 for the servo). Itā€™s fairly intuitive and as such simple. The R: line is just a more compact way to do this but itā€™s not applicable to all scenarios

1 Like

But the thread starts with him showing a mixer that has the format of 8 separate M: lines, and then he states that he is using a simpler mixer now: he then shows the R:8x line and after that a Main1 M: line. I would just like to understand how he did that. Iā€™m comfortable that I could create a 7 M: line mixer.

As an aside, I have 6 rotors, a tilt rotor servo, and 2 ruddervators. Can I make 9 mains or are mains limited to 8 and then I need to go to aux?

IIRC there are only 8 main outputs so youā€™d have to transfer at least one to the aux output.

In my thesis I developed a tilt-quadrotor (4motors + 4 servos) and I used the motors on the MAIN and the servos on the AUX.

In your case Iā€™d move the servo to the aux and maybe the ruddervators aswell.

Hey,
I have an issue with my custom mixer file, maybe one of you could help me out?

My Airframe is very close to the E-Flight Convergence, but i am also tilting the rear motor.
So its a tiltrotor with 3 rotors, all of them can tilt.

To get my rear motor tilting i replaced the ā€œZ:ā€ line with:

M: 1
S: 1 4      0 -20000  10000 -10000  10000

That works, the problem is that after using this mixer file my 8th PWM-output stops working. So one of my elevons is not moving anymore.

Attachend is my ful mixer file:

# E-flite Convergence Tricopter Y-Configuration Mixer

# Motors
R: 3y 10000 10000 10000 0

Tilt mechanism servo mixer
------------------------------
#Center up:2000 down:1000
M: 1
S: 1 4      0 -20000  10000 -10000  10000

#RIGHT up:2000 down:1000
M: 2
S: 1 4      0 -20000  10000 -10000  10000
S: 0 2   6000   6000      0 -10000  10000

#LEFT up:1000 down:2000
M: 2
S: 1 4      0  20000 -10000 -10000  10000
S: 0 2   6000   6000      0 -10000  10000

#Elevon mixers
------------------------
M: 2
S: 1 0   7500   7500      0 -10000  10000
S: 1 1   8000   8000      0 -10000  10000

M: 2
S: 1 0   7500   7500      0 -10000  10000
S: 1 1  -8000  -8000      0 -10000  10000

Any help would be very much appreciated!
Greetings Thomas

It would be helpful to see the outputs of ā€˜pwm infoā€™ as well as ā€˜listener actuator_outputsā€™ from the console.

Thanks for the tip,
i got it working a while ago by just changing the order of the outputs.
I moved the elevons before the tilt servos and now everything is working correctly.