Mixer for Coaxial Helicopter with two swashplates and six servos

Setup

I’m trying to create a Mixer for a coaxial helicopter that has one swash plate for each rotor level. Each swash plate is controlled by three servos (at 0, 120 and 240 degrees). Additionally, each rotor has one motor controlled by an ESC. With this setup I end up with 8 Main outputs. Now I am trying to figure out, how this can be expressed in a Mixer file.

So far I came up with to possible solutions for this. But with each of them I ran into issues and now I don’t know which one is the way to go and how to work around the problems that I ran into.

Here are the two options:

Option 1: Using two Helicopter Mixers

The first thing I thought of was to use two helicopter mixers:

# Upper rotor level
H: 3
T:      0   2500   5000   7500  10000
P:      0   2500   5000   7500  10000
# Upper swash plate servos:
S:      0  10000  10000      0  -8000   8000
S:    120  13054  10000      0  -8000   8000
S:    240  13054  10000      0  -8000   8000

# Lower rotor level
H: 3
T:      0   2500   5000   7500  10000
P:      0   2500   5000   7500  10000
# Lower swash plate servos:
S:      0  10000  10000      0  -8000   8000
S:    120  13054  10000      0  -8000   8000
S:    240  13054  10000      0  -8000   8000

According to the documentation on helicopter mixers, they

combine three control inputs (roll, pitch, thrust) into four outputs (swash-plate servos and main motor ESC setting).

So, using the two helicopter mixers, all my 8 outputs are covered. The problem is, I didn’t yet connect the yaw control (control group 0 index 2) to any output. A helicopter mixer kind of assumes that there will be a tail rotor to control the yaw. However, my coaxial helicopter doesn’t have a tail rotor and shall controll the yaw by different turning speeds at the two rotors.

Is it possible to integrate this functionality into the two combination of two helicopter mixers?

Option 2: Using 8 summing mixers

The other option I thought of was doing with 8 Summing/Simple mixers. There is a mixer ROMFS/px4fmu_common/mixer/coax.main.mix that is doing this for a coaxial helicopter. The thing is, that the coaxial helicopter that they are doing it for is a lot less complex then the one I have. It has only one swash plate and two servos on it. It doesn’t have collective pitch which makes the whole thing a lot easier. The problem that I ran into with this option was that I don’t know how I can integrate the collective pitch in this setup. I thought of just adding the control throttle to all servos. So the mixers for the 0 degree servos would look something like this (combining pitch and throttle)

M: 2
S: 0 1  -10000  -10000   0   -10000  10000
S: 0 3  -10000   10000   0   -10000  10000

and the mixer for the other two servos would look something like this (combining pitch, roll and throttle)

M: 3
S: 0 0  10000  10000      0 -10000    10000
S: 0 1  -5000  -5000      0 -10000    10000
S: 0 3      0  20000 -10000 -10000    10000

Is this the correct approach? And if so, how do I need to set the values for the scaling of the throttle input for the servos at 120 and 240 degrees? Is it correct setting them to the same values as the main rotor ESCs? I guess not, but I really don’t know, how to figure this out.

Any help on this issue would be greatly appreciated.

1 Like

@dagar, +1 on this topic.

I’m working on tandem and side-by-side swashplate configurations. Actually, a GNC expert is designing the controls and I’m implementing in PX4. For the sake of experimentation, the HelicopterMixer has been hacked up to duplicate the collective_pitch loop and the constraints are hard-coded.

The yaw correction part of MulticopterAttitudeControl::generate_attitude_setpoint() seemed to be causing oscillation in the side-by-side config. I’ve added a cryptic MC_VTOL_YAW_COR parameter to disable that block.

Any guidance on a design that would help us get it to work and still be able to push upstream?

The hacked mixer (for single plate and the duplication is hardcoded, for now):
Hack approach - Only the first 3 Servos are defined
The second set of servos are defined by the first set
==================================================

H: 3
T:      0      0      0      0      0
P:  -7000  -5330  -3610   1096   5820
# Swash plate servos:
S:    300  10000  10000      0  -10000  10000
S:     60  10000  10000      0  -10000  10000
S:    180  10000  10000      0  -10000  10000

M: 1
O:      10000  10000      0 -10000  10000
S: 3 5      0  20000 -10000 -10000  10000

M: 1
O:      10000  10000      0 -10000  10000
S: 3 5      0  20000 -10000 -10000  10000

@Danduril Nice work, thanks. Did you actually test your branch? Does it work already or is it still WIP?

It’s not yet exactly what I need, because I actually need different scalings on the upper and lower rotor level swashplates. But if this is working for you, I will see if I can manage to adapt it for my needs. Does it really make sense for you to have the same scalings for upper and lower swashplate? Usuaully you would need higher angles and angle changes on the lower plate since the rotor is already in the airstream of the upper one, wouldn’t you?

EDIT: How do you wire your FMU with this mixer? You zeroed out the throttle curve of the helicopter mixer, so I guess you don’t connect these? So you connect the servos to MAIN2-4 and MAIN6-8 and then you connect the main rotors to AUX1-2?

@max11gen, ty. The configuration is side-by-side, not co-axial. Our common issue is controlling two separate swashplates, but rotor config is different. Still WIP.

The motor are controlled by pilot console and same signal goes to ESC for each rotor, ATM. Pretty much constant speed while in flight.

@Danduril and @max11gen This is really cool! I am trying to achieve something similar. I want to build a coaxial helicopter (2 Motors) with a double swashplate which is linked mechanically (3 servos). Yaw would be controlled by changing the motor speeds diferentially to have different torques.

I also have oscillations in pitch and roll, which might come from the large yaw error. I will give this a try tomorrow.

Has there been any progress on this topic?