Dual-Heli frame (FRAME_CLASS 11) Problem

This new frame type was added in 3.5 but AFAIK it hasn’t been tested until now.

I have a problem with servos throw, they go to extreme with slight stick input or board movement.
I set H_CYC_MAX down to 300 to get reasonable throw (default = 4500) but still unflyable.

Parameters: 352.param (13.8 KB)
Log: 2 1-1-2000 7-22-06 AM.bin (947.8 KB)
Board: Cube

Additional info: I have been flying my synchropter with custom 3.4.5 code fine. Later decided to move to 3.5 and modified the servo mapping as usual but it had this same problem (plus few more) so I thought it was my bad coding but using official firmware does the same.

hi, I’ll have a look at your log shortly

this is a transverse heli, right? In that case you need H_DUAL_MODE=1. Otherwise it’s setup as a longitudinal dual.
I know this probably doesn’t explain all your results, but it won’t work well with that setting

Thanks for the help!

First is to check whether this problem is in the code or my incorrect parameter(s).

Neither transverse nor tandem dual mode will work on my frame, I use custom firmware modified from AC3.5.
The log I posted uses the official 3.5.2 heli firmware so I left things untouched since it won’t work anyway. (just ruled out my bad custom code)

Here is my modified code which has the same problem:

Pitt,
Have you found a solution to this issue? It was interesting to see that the guys tuning their tandem aircraft had gains about 10 times less than what is typically used for single main rotor/tail rotor helicopters. Sounds like you are encountering the same thing. It has to be some scaling that is being done differently in the Heli_Dual motors library as compared to the Heli_single motors library. I tried looking through your Copter 3.4 motors library compared to the 3.5 motors library. You might clone the 3.5 repository and then copy your Heli_Dual motors file into the repository. Then do a “git diff” to see how they changed. it might reveal where the issue is. Just some thoughts.
I think it is very interesting that your 3.4 version works as expected and the 3.5 version has some scaling issue.

@tridge and @PittRBM, I think I may have found an error in the 3.5 Heli_Dual motors file in comparing it to the Heli_single motors file.

This is from the Heli_Dual file

float servo1_out = (_rollFactor[CH_1] * roll_out + _pitchFactor[CH_1] * pitch_out + _yawFactor[CH_1] * yaw_out)/0.45f + _collectiveFactor[CH_1] * collective_out_scaled;
float servo2_out = (_rollFactor[CH_2] * roll_out + _pitchFactor[CH_2] * pitch_out + _yawFactor[CH_2] * yaw_out)/0.45f + _collectiveFactor[CH_2] * collective_out_scaled;
float servo3_out = (_rollFactor[CH_3] * roll_out + _pitchFactor[CH_3] * pitch_out + _yawFactor[CH_3] * yaw_out)/0.45f + _collectiveFactor[CH_3] * collective_out_scaled;
float servo4_out = (_rollFactor[CH_4] * roll_out + _pitchFactor[CH_4] * pitch_out + _yawFactor[CH_4] * yaw_out)/0.45f + _collectiveFactor[CH_4] * collective2_out_scaled;
float servo5_out = (_rollFactor[CH_5] * roll_out + _pitchFactor[CH_5] * pitch_out + _yawFactor[CH_5] * yaw_out)/0.45f + _collectiveFactor[CH_5] * collective2_out_scaled;
float servo6_out = (_rollFactor[CH_6] * roll_out + _pitchFactor[CH_6] * pitch_out + _yawFactor[CH_6] * yaw_out)/0.45f + _collectiveFactor[CH_6] * collective2_out_scaled;

This is from the Heli_single motor file
float servo1_out = ((_rollFactor[CH_1] * roll_out) + (_pitchFactor[CH_1] * pitch_out))*0.45f + _collectiveFactor[CH_1] * coll_out_scaled;
float servo2_out = ((_rollFactor[CH_2] * roll_out) + (_pitchFactor[CH_2] * pitch_out))*0.45f + _collectiveFactor[CH_2] * coll_out_scaled;

Notice that in the Heli_single file that the 0.45 factor is multiplied but in the Heli_dual file they are divided by 0.45. I checked Pitt’s 3.4 version of the Heli_dual motors library and he has the 0.45 factor multiplied similar to the Heli_single file.

Hope this fixes the problem.

By the way this would result in a amplification factor of aproximately 10.

Pitt,
I submitted a issue on github regarding this problem. Here is the link to it
Overly sensitive swashplate to cyclic inputs for Heli-Dual frame

Regards,
Bill

Thanks a lot!

So @frizensami 's problem months ago was caused by this as well?
I did looked at 0.45 in the code but didn’t noticed that the signs were off :expressionless:

By the way, what’s the use of 0.45 multiplier?
A comment in the code said it has something to do with default 4500 CYC_MAX but I don’t understand it.

I don’t know if this causes other issues. But I’m pretty sure this is what caused the extremely low gain values for his tuning.

I’m not sure. I haven’t really sat down and figured out what each line of code is doing in the motors library.

Hopefully this is a quick fix that can get you flying 3.5.X.

Hi pitt, I was wondering if you could clone the latest stable version of 3.5 and implement the changes that I suggested to fix the sensitivity problem. If you were convinced that my solution fixed the problem, then you or I could also submit a pull request and attach that to the issue that I posted. Let me know.

Please wait a bit, I should have time this weekend.
I’m having exams this week.

I’ll post report here :slightly_smiling_face:

Uploaded to my heli.
Servos seem to work at reasonable range now.
:grinning:
I will test flight when the weather gets better.

Sounds promising. I will wait for your test results.

I am trying to set up a transverse rotors. I use Mission planner to view the servo output, but motor 1-4 seems to show a single rotor setup with tailrotor servo. should I get motor 4-6 works as the 2nd swashplate?

I recommend starting a new thread.

Have you set your FRAME_CLASS to 11?
Are you using heli firmware?

1 Like