Improper handling of swashplate servo trim causing unequal cyclic output from one side to the other

I am starting a new thread to highlight this issue. This is not a critical bug but will affect the swashplate response and cause coupling.
@Felix recently discovered that swashplate trims were not properly accounted for in the swashplate movement showing that he had more cyclic blade pitch in one direction than the other. It was presented here. Concerned that it was potentially due to mechanical servo arm travel, he further looked at servo output values to verified the issue here.
This was investigated by looking back at previous versions of the Copter code. In version 3.3.3, the servo calculation was performed in pwm units and the delta between servo midpoint and servo trim was added to the servo_out calculation so that it was accounted for when the pwm was sent to the servo.
In the Copter 3.4 and subsequent, the servo_out calculation has been rescaled to 0 to 1 and the shift of the servo_out value to account for the off center trim was removed. The servo_out calculation is then rescaled to -1 to 1. I guess it was thought that servo trim would be properly accounted because the 0 point is the trim servo point. However the swashplate pure movement relies on all three servos moving equal distances and this can’t occur because with trim values other than 1500 the scaling of output depends on the difference between the endpoint and trim value. For example, Let’s say a collective input is made. The servo out calculation for all three servos before rescaling would be lets say 0.75 (0 to 1 scale) and would be 0.5 (-1 to 1 scale) which would be converted to pwm before sent to the servo. Let’s say one servo had a trim value of 1600 and the other two had trim values of 1500. the conversion to pwm for servo out values > 0 is:
pwm = servo_out *(servo_max- servo_trim) + servo_trim
which for the first servo would be
0.5 * (2000-1600) + 1600 = 1800
the other two servos would be
0.5 * (2000 - 1500) +1500 = 1750
thus causing a cyclic input when only collective input was desired.

@Felix
Here is a link to download the firmware. If you are using mission planner then you will have to click on the load custom firmware button on the initial setup tab under the install firmware section.
https://drive.google.com/file/d/12FtvdYsYI4pomW3ZiRAAaCIORqmH6fde/view?usp=sharing
Let me know if you have any issues downloading or installing the firmware. Treat this as alpha version software. Be sure that you are happy with the swashplate response through rotors static ground tests. I have tested it in the SITL for a CCPM setup and everything appears to be working as expected. I have not tested the H1 swash nor have I implemented any changes for the dual-heli or quad-heli frames. I wanted to make sure this works before fixing the rest of the frame types.

@ChrisOlson also plans on testing this.

Regards,
Bill

Hi Bill,

Which branch do you have this in?

Rob

Rob,
The branch is swash_servo_trim. Here is a link https://github.com/bnsgeyer/ardupilot/tree/swash_servo_trim

Hi Bill!

Thank you for your very kind introduction and the detailed explanation of the problem and your findings. That really makes sense.

I just installed the new firmware. Unfortunately I’m still experiencing the described problem. Mission Planner is showing me that I’m running “Copter V3.5.5 bnsgeyer V1.0 (5fb9d809)”. I had to set H_COL_MAX and H_COL_MIN again. H_COL_MID was fine. I also reduced H_CYC_MAX to 25 (which was on 26.2).

When I’m testing it in manual mode now I’m getting 9.8 deg with roll right and 5.4 deg to the left. So the problem actually got worse. Could it be possible that it’s just correcting the problem in the wrong direction?

The servo outputs are:
Stick:__ left middle right
Servo1: 1300 1510 1733
Servo2: 1265 1427 1711
Servo3: 1488 1488 1488

Hi Felix, I’m sorry to hear that. I Soum by saying manual mode that you had the parameter H_SV_MAN set to one? Could you post a log file of this test? I think that would help. Just remember you’ll have to set log disarmed equal to one in order to log data while the aircraft is disarmed. Thanks!

Hi Bill!
Yes, exactly. In Mission Planner it’s the “manual” button in the heli setup page. But it’s the same as setting H_SV_MAN = 1.

You can find my logs of a similar test here:

A short explanation what I did: At first I powered it up, waited for Mission Planner to connect, pressed the safety switch, and clicked the buttons “zero” “max” “zero” “min” ( = H_COL_MID/MAX/MID/MIN). Then I clicked “manual” (H_SV_MAN = 1) and moved the collective to the point where my pitch gauge showed 0 deg. It took some time. You can see the servos moving slowly to the perfect position.
Then I moved my cyclic stick to the right end and waited a moment, then back to zero and finally to the left side.
I hope this helps.

@Felix,
I think I know what I did wrong. I didn’t handle reversed servos properly with my implementation.

@Rob_Lefebvre and @ChrisOlson
So the way I see it, we have two options for handling this.

  1. Calculate the servo throw from trim using servo reverse, min, trim and max properties in the move_actuators function. This would require making the change to all of the frames that use swash plates.
  2. Make a new function that is used instead of the calc_pwm_output_1to1 function which is in the AP_Motors_Class.cpp file. or should this be a polymophic type function? if it was polymorphic then it would need to be defined in multirotor and in heli class.

Initially I thought I would want to do it in the move_actuator function for each frame. Now I’m thinking this should be a function that replaces or is used instead of the calc_pwm_output_1to1.

Thoughts?

EDIT:
Thinking about this more, I don’t want to make this function polymorphic. Only the swashplate servos need to be controlled this way. So I plan on making a new function within the motors_Heli class to support calculating the PWM for the swashplate servos.

@Felix
I think I got it now. I did testing in the SITL and verified that it works with the servo reversed. Here is a link to the file for your PH2.1
https://drive.google.com/file/d/1Yy9sE4yFZpIvDRxVMBoiys6ytwAtfVFY/view?usp=sharing

Again I have only changed the behavior for a trad heli single main rotor/tail rotor configuration. I will have to follow up with the other trad heli frames. Here is the link to the updated software. I have done a forced commit so be sure to pull the branch accordingly if you are looking to build the software.

1 Like

Hi Bill!
You got it. The Problem definitely occurred because of the reversed servos. I installed your new firmware and can confirm that the cyclic pitch is now equal in both directions. At least on one side of the rotor. When I turn the rotor 180 deg there is still a little bit of difference left. I get 8.3 deg with roll right and 7.4 deg with roll left. But checking the servo monitor showed that the output signal is okay:

Stick:__ left middle right
Servo1: 1283 1514 1749
Servo2: 1195 1429 1662
Servo3: 1489 1491 1489

So it seems your code is working perfectly now!
I removed all servos to ensure the arms are perfectly trimmed in a 90 deg position to the case (and to the links). Then I adjusted the lengths of the linkage rods again and did the fine tuning with the servo trims (only a few microseconds) so that the blades are at 0 deg of pitch in every position of the rotor. I’m sure, my head setup is very precise now. I still can see the little difference in cyclic, so I guess it’s one of my servos moving a little bit less than the other one…? But I think the accuracy should be sufficient for flying now. As I said, the code seems to be working as expected. Thanks a lot for that!

Great! Glad to hear it works as expected. I will continue to modify the other frames and PR it into 3.6. I have an idea of how to modify the code to remove the coupling introduced by arc of the servo arms, but I will work on it and push it at a later date. I want to get this into the code first. Thanks for your testing.

V/R,
Bill

Like I said in my previous post, I will modify the dual heli frame so that the swashplate servos behave properly so as to not introduce coupling like I have explained in the initial post. However I am not sure whether I should apply this fix to the quad heli frame. Quad heli’s are four variable collective pitch propellers. I think it would be important that the servo throw not be affected by off center trim values. Unless there is anyone that thinks I shouldn’t modify the quad heli like the others, please let me know. I’d be interested in your experience with that frame.

Hi Bill!
That sounds very interesting what you’re writing about the arc of the servo arms. I’m looking forward to testing it.
Thanks also for thinking about the other frames. For the quad heli I think it should be just the same. An offset of the servo shouldn’t affect the min/max position of the pitch slider. But I’m also not an expert for quad helis…

Have same problem, would like to have perfectly trimmed swashplate, have trimmed perfectly at mid position, but at max position left servo is for ~1mm upper and at min position is for ~0.5mm lower than another servos.

In servo output configuration page in MP just trim function/values working, not working Min or Max values, changing this values does not make any effect.

This mean when i will up to full throttle - heli will a little bit drift to the right, so in 3D fly it will be very difficult to hold heli as you wont.