Issue with adding a new Frame Class for the Heli Frame Type

@tridge or another developer familiar with adding frame classes
So I integrated a compound heli frame class into arducopter. I got it to compile but when I go to arm the aircraft (after changing the frame class to the new one I developed), I get a message to check the frame class. I tried using the Dual Heli frame and got the same message when I tried to arm.

I tracked this error to the MotorsHeli.cpp file and the init and set_frame_class_and_type methods. In particular, I guess the init method is hardcoded for the motor_frame_heli frame class.
// record successful initialisation if what we setup was the desired frame_class
_flags.initialised_ok = (frame_class == MOTOR_FRAME_HELI;

Once I changed this to MOTOR_FRAME_HELI_COMPOUND and the other statement in set_frame_class_and_type method, it armed. So how do I fix this issue.

Here is my branch if you are interested.

Hi Bill,
You need to make AP_MotorsHeli::init a virtual function, then add an init function to AP_MotorsHeli_Compound. Then in AP_MotorsHeli_Compound::init() you should check that it has the HELI_COMPOUND frame class.
The same is needed for set_frame_class_and_type()
I’ve pushed a patch to your branch here that fixes it (untested):


In general you should use virtual functions like this to specialise the compound heli backend, calling the parent class functions as needed to save on duplicate code.
Cheers, Tridge

@tridge I didn’t see it implemented this way in master or 3.5.4-rc1. I realize that we don’t have many users with dual or quad heli configurations but they would definitely get this error when trying to arm. Right? Do you get this error when you try using the quad or dual heli frame classes?

@tridge, So I looked into this further because I thought it was strange that other users have not brought this up. So I never rebooted the controller after making the frame class change. if I reboot the controller then I don’t get the error when I try to arm. I can’t remember but I believe it does say that you have to reboot the flight controller after changing a frame class.

So I’m guessing that this is not an issue after all. Let me know what you think.

Regards,
Bill

They both work fine (I setup a new quad heli yesterday).
The reason they work is this line of code:

I think it would be better if the approach I gave above was used, but what is in there does work.

it is not an issue for users, but the code could be made clearer

That line of code is what I needed. Thanks for your help!!!

So I have one other question about the implementation of the boost control. Currently I have it hardcoded to RC 7 and an if statement regarding the frame class decides whether the boost is set. Does it make sense to have boost as an CHX_opt aux function? In looking at these it seems they are used more for switches rather than analog controls. Ultimately I plan to put the boost as a separate function “set_pilot_desired_boost” that would be consistent with other controls. this would require making sure it is inserted in each of the control_auto, control_acro … functions for each of the flight modes. In each case I would have to use an if statement regarding the frame class.
Thoughts?

yes, I think that makes sense. While it is mostly used for switches, there are some cases where its a analog control (eg. TUNE).

you could have a control_add_boost() function which has the frame class check inside it, then just call that function from appropriate places.
Also, why isn’t boost appropriate for a multicopter?

So currently I have the set_boost method as a virtual function in MotorsHeli and then I have it in each of the heli frames motors as a method. Do you suggest that I put that as a virtual function in Motors.cpp so it can be used by any frame, multicopter or heli?

So if I make this a aux function then I would set the if statement based on the activation of the boost aux function and not the frame class. So if other frame classes wanted to use a boost motor that was independent, a boost function could be added on the servo side (unless there is already a function that does this). Thus activation of the two could enable use of the boost feature. This would give maximum flexibility to set the input and output on whatever channel the user chooses. But it requires some knowledge of how to make it all work. In the compound heli case, because the boost is not independent and is coupled with directional axis, the compound heli case requires a special frame class.

we really need to ask @rmackay9 about that. I think it would make sense, but Randy would make the decision.