Servo outputs in AP_MotorsTailsitter.cpp: buggy?

I am building a bicopter, which I could make fly yesterday. It has flaps instead of motor gimbaling (the control laws are nearly identical, however), but otherwise it is a standard bicopter (Copter firmware, FRAME_CLASS=10).

And I have two questions now, which seem to qualify as bug reports.

  1. Bicopters have a left motor (function 73), a right motor (function 74), a left motor tilt servo (function 75) and a right motor tilt servo (function 76). However, if the outputs are configured this way, and if servo reversals are set such that they counteract pitch changes, they accelerate yaw changes, resulting in wild yaw spinning. The following video illustrates that. One case was clockwise, another one counter-clockwise, and one can see the flaps actually maximizing yaw rotation speed as much as possible, to their maximum deflection.

To make it work, one needs to set the right motor servo to the left tilt function, and vice versa. Again, same would happen if one uses actual motor tilting instead of flaps.

One more note is that the Complete Parameter List mentions function 75 as TiltMotorFrontLeft and 76 as TiltMotorFrontRight. There is no other choice in the Copter firmware, but the sources also mention function 46 (k_tiltMotorRearLeft) and 47 (k_tiltMotorRearRight) with “rear” instead of “front”. In the same sources, however, function 75 is named k_tiltMotorLeft, without any indication that it is about a front motor.

So it looks like some refactoring was not as smooth as expected: it might possibly be that the effect of tilting a front left motor should be the same as tilting the right motor of a bicopter, but the particular outputs in AP_MotorsTailsitter.cpp have the wrong sign in any case.

  1. Checking that further led me to more confusion. Lines that produce servo outputs are exactly as follows:

However, in bicopters in particular, and to some extent in dual-motor tailsitters too, one cannot just map the desired pitch/yaw thrust to servos that tilt motors (or that control flaps), since that thrust is a fraction of the motor thrust.

Note that e.g. CoaxCopter does the right thing in a similar place.

This problem should manifest itself either on higher-than-hover or lower-than-hover thrusts as over-actuation or under-actuation correspondingly.

Before I delve into trial-and-error, could @iampete, @rmackay9, or any other guys, please check whether this analysis makes sense?

There correct for tilting motors, your using them for elevons.

Your right, it is not implemented in copter but we have lots of options for tailsitters on plane. See:

I see: this one changes the sign depending on whether the point where we apply the force is above the center of gravity, or below it. In a typical tiltmotor, it is above, in a flapped vehicle it is below. Got it!

I will try to fix the second thing then. It seems like, unlike planes, there are fewer options - but one would also like to account for the additional yaw moment when rolling, which is also not in the Copter’s codebase now.

@iampete am I right that one cannot currently read the vehicle’s attitude (e.g. pitch) from a subclass of AP_Motors?

Or maybe AC_AttitudeController is a more suitable place to take care of too-high or too-low center of gravity? It seems that quadcopters have decent authority against the impact of the off-center CoG by just using I-terms, but in bicopters pitch is too quick to rotate but has relatively poor authority.

Right, AP_Motors should not need to know attitude. AC_AttitudeControl is the right place for such things. You may have to add some methods so you can pass the right numbers on to motors.

I’m not sure I understand the problem your having, maybe you can explain in more detail?