SERVO TRIM values not portable form 3.3.3 to 3.4.6 and later release of tradheli

I think there is an issue in heli in 3.4.6 and later which can be serious in some situations. In the old code the user throttle values were basically scaled to ( H_COL_MIN, H_COL_MAX) and then adjusted using the trim/servo reverse value. This meant that the whole scale of the valid servo values are used linearly.

However in the later versions ( 3.4.6 onwards) the user throttle value is mapped to ( H_COL_MIN, H_COL_MAX). Then value of (0.5) is set to trim values and any higher or lower values are adjusted accordingly. Generally this should work fine but I see issues when .5 is not in the range Eg. ( H_COL_MIN, H_COL_MAX) mapped to ( 1200, 1480). In this case no value of throttle will map to 0.5 ( the valid range will be between ( 0.12 to 0.48). So one side of the trim values will never be used. This does not look right, unless there is a reason to do so. Perhaps adding a warning would be in place if the H_COL_XX range does not encompass the value 1500. If I am missing something then please let me know.

I found this issue when I tried to upgrade my nitro from 3.3.3 When I copied the old trim values the swash was tilted to one direction. Then I investigated it further and I found this. If the H_COL_XX values are symmetrically distributed around the value 1500 then it will not be a problem. Of course if the user starts from scratch then there will be no issue.

@Sunit_Pal there were so many changes from the 3.3.3 code to 3.4 that I think a complete new setup is required for 3.4. Even the PID scaling is different. Without looking for sure, it seems to me some scaling factors were put in for multi-rotor aircraft to make the transition. But for Trad Heli, not so.

Even transitioning from 3.4 to 3.5 requires some careful manual entry of changes because things like the H_SVx_ params were moved to SERVOx_ params with new SERVOx_FUNCTION that must be set to correspond to the servo postion and motor number. A working setup in 3.4 was broken in 3.5 for me by just loading the firmware.

This is definitely a bug in 3.4.6 tradheli and later and needs to be fixed. Here is the problem. The throttle is scaled to [0-1.0]. The values 0.5 is mapped to the trim servo position and the left hand side is SCALED to remaining values from 1000 to trim. The right hand side is SCALED from trim value to 2000. This SCALING is an issue. This means for a certain increase in pitch the 3 servos might move to different values. This will cause the swash to be level are mid position but tilted at top and bottom position.
I think the better way to just increase the values from trim values and not scale them. I did locally made this change and it seems to be OK. I would like second opinion from other tradheli enthusiasts.
The code change in 3.5.3 is as follows in function “AP_Motors::calc_pwm_output_1to1” of file “AP_Motors_Class.cpp”

if (input >= 0.0f) {
    ret = ((input * (servo->get_output_max() - servo->get_trim())) + servo->get_trim());
} else {
    ret = ((input * (servo->get_trim() - servo->get_output_min())) + servo->get_trim());
} 

Needs to be replaced with.

if (input >= 0.0f) {
    ret = ((input * (servo->get_output_max() - 1500)) + servo->get_trim());
} else {
    ret = ((input * (1500 - servo->get_output_min())) + servo->get_trim());
}

This will shift the servo out value by trim but not scale the output value.

This is the way it was in 3.3.3 and I see no reason why it should not be this way in later release.

I am flying Missions with my Helicopters. Inside the Pixhawk is the patched code for Copter 3.5.3 from Chris Olson. There is not a bug there what I can see. Use the new way of Heli tunig and you good as gold. But you can stay with 3.3.3 which I liked very much in the past.

I am using 3.5.3 for missions and aggressive flying. It works great. I do not mean that it has a bug so that the heli is unflyable. But let me illustrate an issue with an example.

Imagine a setup with H_COL_MIN/MID/MAX set to ( 1250/1500/1750) and the servo trim values are 1300/1500/1500. None are reversed. Notice that one of the servos has a bit extreme trim values but that is when the bug shows up.

At throttle .5 the servo output values will be : 1300/1500/1500. ( This will be setup to have no roll/pith and the swash plate will be flat).
At .25 throttle the servo values are: 1225/1375/1375
At .75 throttle the servo values are: 1475/1625/1625

As you can see at .25 servo 1 is moved by 75 while servo 2/3 is moved by 125. This will cause the swash to tilt in one direction when no roll/pitch control is applied.
Similarly at throttle .75 servo 1 moved by 175 while servo 2/3 moved by 125 causing the swash to tilt in the opposite direction without any roll/pitch applied.

You can experiment and see that these values are correct by setting the param values in heli firmware and looking at RCOUT values in mission planner.

This can be taken care of by just shifting the final servo value using the servo trim values and scaling the value using the trim values as I have shown above.

For most of the heli this will not be a problem as the trim value is usually not this crazy. But I have a very old heli in which I cannot make mechanical changes and hence I see this issue there, as the trim values are extreme.

@Sunit_Pal you could post this to the Developer section of the forum so we could take a look at it. IMO setting up with one servo at 1300 trim would be not a good idea due to running out of cyclic control at full collective pitch range, in this case in negative pitch. I would be better to trim that servo at 1500, pull the horn off the servo shaft and move it to the next spline on the shaft to get it closer, then trim from there. 1300 is 40% of the servo’s possible sweep range from it’s middle travel to minimum and one spline change on the horn should accomodate that. It is possible servos have been built where you can’t remove the horn and move it on the shaft, but I’ve never seen one.