Looking for good X-Plane Helicopter (please suggest a model you have parameters for)

I am aware about Tridge’s Index of /XPlane but those parameters does not fly well with recent ArduCopter, or XP11 (whichever is the reason)

@Andre-K what is your goal. What are you planning to do with it. I suspect most X plane models are of full scale helicopter. I know that the full scale helicopters will be a little more challenging to tune.

@bnsgeyer it’s for a research project, where Ardupilot is to do aviation in an urban environment.
The ultimate airframe to visualize would be one of the people-carrying multicaopters, but real heli is the closest, except I am not so familiar with tradheli tuning.

@Andre-K are you able to build the code and run SITL? If so, I suggest you use my most recent alpha release of autotune. Here is my branch based on 4.1 that my users are currently flying. Here is the link to the release page that contains the instructions on using it. Since it’s a simulation, I would expect to get much cleaner results.

One thing to remember with the full scale versus rc model heli’s is that the full scale hover left skid low while the rc heli’s hover right skid low. That just means that the ATC_HOVR_RLL_TRM param has to be negative for your sim model.

@bnsgeyer Fantastic ! - I just built pr-autotune-2 and will follow the release page instructions tomorrow. - must set up my X-Plane (usually used for flight simulation without Atdupilot)
Autotune for traditional heli must be a very welcome feature.
Thank you.
I’ll let you know how it goes.

@Andre-K let me know what aircraft you plan to use. I suspect we will have to reduce the min and max sweep frequencies.

EDIT sorry I was thinking your building VTOL.

@bnsgeyer I am trying to use Bell Jetranger 206
-right now I run into some problems with the instructions on:
https://ardupilot.org/dev/docs/sitl-with-xplane.html
I am not sure whatever the instructios saying “$ modules/waf/waf-light plane”
should really say “copter” instead of plane, - in any case, the command

build/sitl/bin/arduplane --model xplane

works as expected, but the mavproxy.py --master=tcp:0.0.0.0:5760 --console
just waits for heartbeat…
This part we had running at work, so I should be able to get it working again …

@Andre-K Read down below in the instructions that describe starting the sim for the heli.
The way you are building and running it is a little different to how I typically do it. This is what I think you need to do

You should put heli like below to build the heli code
modules/waf/waf-light heli

Then you would run it with this command
build/sitl/bin/arduheli --model xplane-heli

It explains some other special things you will need to do to be able to enable/disable motor interlock.

@bnsgeyer
Thank you.
Yes, I am I am usually starting thing using sim_vehicle…

The second line needed a small change, but your suggestion works

modules/waf/waf-light heli
build/sitl/bin/arducopter-heli --model xplane-heli

Anyway- I got It running now as sim_vehicle - troubleshooting now why LOITER always fly forward and loses altitude (using Tridge’s old param file)

@bnsgeyer I did change ATC_HOVR_ROL_TRM from 300 to -300
The copter has a bias to do forward flight at >25m/s - beacuse when the airframe is level (pitch=0) then the rotor is tilted forward.
A 2.5° pitch up make it hover in stabilize. (is that critical for tuning?)
The worst part is that the autothrottle is all over the place, between 0 and 100% - makes it loose altitude slowly while tuning.

Please see attached log:

https://drive.google.com/file/d/1qvF7jKUc28R5lDDPZTdTDWfLKF8ZlaQe/view?usp=sharing

@Andre-K

Yes. You will need to adjust the AHRS trim to make the flight controller attitude read 0 deg pitch attitude for a no drift hover. I think you will have to set AHRS_TRIM_Y to 0.0436 which is 2.5 deg in radians

So I am guessing that the PSC_ACCZ_P gain is too high. You may need some D gain as well but I would try lowering P gain first.

We never talked about min and max sweep frequencies. For that aircraft, I am guessing that that you will want to start at 3 rad/s for min and 20 rad/s for max

I am on the road today so I won’t have access to a computer to view the log until later.

@bnsgeyer Thank you, I appreciate your insight and help very much. I suspected the AHRS_TRIM was a solution, but I were not sure it was “as simple as that” with tradheli too.
I also omitted the notch filter, as I were not sure that would help the SIM.

I believe that it is that simple. Re-Referencing the pitch attitude is really the only thing you can do. Your stick has to be at the trim position (RC2_TRIM) in order for the autotune to start. That trim position is associated with zero pitch attitude. Copter doesn’t have a way to specify a trim value other than zero. So we must re-reference the ahrs.

@bnsgeyer
I’ve found a AHRS_TRIM_Y that makes it stand still, - which is pretty level for the rotor, interfere with the autotune which complains about getting the copter level.
I needed to reduce PSC_ACCZ_P all the way down to 0.12 or so , because 0.5 produced wild collective jerking.

I could not use the recommended settings from “Attitude Controller Setup” - because then the copter becomes so unstable, that it crashes within short time.

Files are here:
https://drive.google.com/drive/folders/1Wagtn9lTvQNqTjq9xlRu3fuNLep0Xn7L?usp=sharing

The big tuning session 00000016*.bin may be of some interest… maybe.
The resulting PID’s are in the bell206_results.param
00000018*.bin is a test flight, it shows far from good results. the copter is not even able to get to GUIDED position. (at this point I also suspect compass issue)

Any attempt on tuning Max Gain, Rate D and Rate P ends up with extreme manouvers, and the main rotor gets ripped off.

@Andre-K I was looking over your data. I saw that you left the AUTOTUNE_FRQ_MAX and AUTOTUNE_FRQ_MIN at the default values. You will need to set them to the following for this aircraft
AUTOTUNE_FRQ_MIN = 3
AUTOTUNE_FRQ_MAX =20

If you can get the frequency sweeps completed for each axis for the ANGLE_P tuning and post them, I probably can figure out the Rate P and Rate D gains. The angle_P tuning that you conducted did not work because the min frequency was too high. Please conduct the ANGLE_P tuning for each axis in separate flights so the log file sizes are manageable.
thanks
Bill

@Andre-K Also I wanted to have you disable the ATC_RAT_XXX_FLTE and ATC_RAT_XXX_FLTD. You can leave the ATC_RAT_XXX_FLTT filter at 20. There is enough time delay due to the nature of this aircraft. Don’t need to add to it in the control signals.

And reset the ATC_ANG_XXX_P gains to 4.5 for all axes before running the ANGLE_P tuning

@bnsgeyer Please see the files named autotune-Y.* in
bell206tuning - Google Drive

I followed your advice regarding FLTE and FLTD, and was trying to tune yaw this time, first with ATC_ANG_XXX_P at 4.5 (but as before, that led to loss of control rather early)
so I set them to 3 (I think I often flew with “2” ) - but failed in the usual way.
Status is: it flies “acceptable” in STABILIZE, LOITER/POSHOLD but is not good enough for AUTOTUNE

Is there a particular order you recommend for AXES and AUTOTUNE_SEQ items ?

At this point, I just want a sweep in each axis using the angle_p tuning. You can stop the tuning after the sweep. One thing that I forgot to mention with angle_p tuning is that you can fly the aircraft while it is doing the sweep. That way the user can help keep it the aircraft from drifting too far. In your case, you can help keep it in a stable hover. It will kick you out of the autotune if you put more than 5 deg of correction. You can probably also raise the Rate p gains in pitch and roll to help stabilize the aircraft.

@Andre-K from looking at a SITL model I tried tuning of a bell 206, I had Rate P and D gains pretty high. Rate P gains were over 1 and rate D gains around 0.1. So I think there is room for you to increase the gains. The issue becomes that the lag in the response is pretty high. You might do better tuning the S-76 helicopter. I saw that that helicopter is one of the xplane selections.