How do I reduce throttle "pulsing" in auto modes?

I have significant experience with APM in multi-rotors but just put one in a plane for the first time.
The plane is a Skyhunter and is running very well, except for one thing.

The throttle constantly “pulses” in auto, cruise and sometimes loiter. With my original settings this was very significant and rapid at about 2 Hz.

I’ve done the following trying to reduce it:
Turned THR_SLEWRATE all the way down to 20.
Added an airspeed sensor, enabled it and changed the following:
TECS_PITCH_DAMP up to 0.5
TECS_THR_DAMP all the way up to 0.9 documentation says 1.0 is the limit but I can’t tell if that’s a hard limit and didn’t want to have something bad happen.
TECS_TIME_CONSTANT up to 7.

It’s much better than before but still seems to have a problem. Pitch/Altitude works amazingly well by the way. Very smooth and solid with no overshoot.

Throttle is still modulating at about 1Hz and about 20% of the throttle range.

What else should I do?

What things should I look for in the logs? I’ve not downloaded any yet since getting a USB cable into my fuselage is not possible so I’d have to do some disassembly for that. I don’t normally fly the plane with telemetry connected but could do a short-range flight with it for testing if the tlogs provide enough info.

Since it’s raining around here, I took the time to disassemble things and download the data logs.

Unfortunately, only ground tests were resident. I also made a hole in the side of my fuselage so in the future I can connect USB without taking things apart.

Since APM:Plane doesn’t require arming by default, what process should be used to close out a log file? Is just disconnecting the plane’s battery OK?

I’ve spent considerable time on this one, and have found two things which help:

  1. Use data-flash logs to find the correct throttle for your selected cruise speed. Setting this just right helps a little.

  2. Turn TECS_INTEG_GAIN up significantly. This one seems to be the real fix. I’ve just found it, but I know for sure that halving the default of 0.2 to 0.1 made the pulsing considerably worse and doubling it up to 0.4 made things significantly better. I don’t know how far I can go with this and there’s no in-flight tuning like arducopter so I think I’ll just go by 0.2 and see what I find.

Turning the throttle slewrate down to 0.1 masks the problem pretty well but has other issues (can’t power up fast to climb etc).

It would probably be good to make note of this in the documentation for TECS_INTEG_GAIN.

Sometimes this sort of pulsing throttle can be caused by the throttle damping gain being too high, particularly if you have a high thrust setup that responds very rapidly to throttle changes.

It’s unusual for a larger integrator gain to reduce oscillation, unless the system is hitting an internal limit of some sort. If you have a flash log from an affected flight with TECS logging enabled, I would like to see it.

Thanks,

Paul

Heres a very short youtube video with on-board sound which shows the problem.
[youtube]http://www.youtube.com/watch?v=hEpBLWFsQwM[/youtube]

The attached log is an edited version from the end of the same flight. The part shown in the video was truncated since the flight was so long.

It doesn’t seem to always have the problem. One thing I’ve noticed in my logs is a tiny bit of noise on the throttle input probably from a 1-bit noise error on my throttle stick. I’m wondering if that combined with the throttle nudge feature is causing it. I think I’ll try adding a function on my transmitter to force the throttle to 50% for testing next flight.

I believe I know the root-cause now.

Today I tried flying with THROTTLE_NUDGE disabled and I was unable to get the plane into the pulsing mode shown in the video linked above. All other settings are unchanged from the video flight above.

From examining the flight log, I believe some 1-bit sampling noise on the throttle input gets a very high gain applied to it which badly messes up the TECS system.

If you look at CH3_IN, CH3_OUT and dsp_dem in the attached log file during the Cruise section in the range of 2 to 4 minutes you’ll see that a tiny noise error on the input seems to lead to wide throttle swings with some periodic pulsing. I believe that sometimes gets vastly worse via a feedback mechanism with THROTTLE_NUDGE enabled but I don’t have a log showing that at present.

You will also notice that the throttle input is right at 1500 during most of the cruise section. I configured a switch on my transmitter to force 50% throttle so I wouldn’t have any potentiometer noise from my TX. I believe the noise is probably introduced during the PWM sampling on the APM. There’s a brief part in the middle where I changed back to analog throttle and it happened to not be right on a sampling boundary so the TECS noise doesn’t show up.

The spkes on dsp_dem show up directly in the throttle output. In the middle area (around the 3 minute mark) where dsp_dem is not oscillating, the throttle output is much smoother.

I did some auto-mode flying earlier in the mission and the throttle output is nice and smooth with throttle_nudge disabled.

I’m using single-wire composite PPM between my RX and the APM btw.

I’m not sure what I can do from here other than learn the code, and add a small moving average filter to the throttle input. From a brief look, it seems that Cruise and FBWB use a special throttle mode which might have problems, but I think the real issue is noise introduced sampling the throttle input.

My previous conclusion that INTEG_GAIN was making a big difference was probably wrong. I may have just happened to have the throttle in a bad position when I tried the low value for INTEG_GAIN. My current value of 0.35 seems to work great though when in auto and with nudging off.

The reason I care about this is because it has a serious negative impact on power consumption and can cause some jello.

Really great work - I’ll get this to Paul. You are absolutely right about the root cause, I see it in the code.

We differentiate _TAS_dem:
AP_TECS.cpp line 280

We use that differentiation as our specific kinetic energy rate demand:
AP_TECS.cpp line 334

We use that specific kinetic energy rate demand to compute our specific total energy rate demand:
AP_TECS.cpp line 354

We pass that through to throttle in a feedforward:
AP_TECS.cpp line 382

We also pass it through to throttle through the throttle damping gain:
AP_TECS.cpp line 385

groups.google.com/forum/#!topic … cRCJyaRzQY

Also confirmed no filter on _TAS_dem

Thanks Jonathan!

Can we get your parameters?

This is the version with nudge turned off.

Plane is a Skyhunter on 4S with SK3 3548-840kv motor

The second log file I posted is much better for seeing the throttle input noise btw.

I’ve had a chat with Paul about your log - noise in the demand is not the problem. Most likely, you have an overpowered plane and you will need to set THR_MAX, MIN_SINK_RATE and MAX_CLIMB_RATE correctly per the TECS tuning guide.

I would start by setting your relevant gains back to default:
TECS_CLMB_MAX 5.0
TECS_SINK_MIN 2.0
TECS_TIME_CONST 5.0
TECS_THR_DAMP 0.5
TECS_INTEG_GAIN 0.1
TECS_VERT_ACC 7.0
TECS_HGT_OMEGA 3.0
TECS_SPD_OMEGA 2.0
TECS_SPDWEIGHT 1.0
TECS_PTCH_DAMP 0.0
TECS_SINK_MAX 5.0
THR_SLEWRATE 100

Then carefully follow the TECS tuning guide. Can be a bit difficult without a partner who knows what they’re doing, but TECS_SINK_MIN and TECS_CLMB_MAX (and THR_MAX) determine the gain of the controller. It is expecting them to be filled in with values measured at the same airspeed. Do the experiments and then follow the second section in the TECS tuning guide to get rid of oscillations.
plane.ardupilot.com/wiki/tecs-to … ing-guide/

It had the exact same problem with everything at defaults btw.

The second log clearly shows the oscillations of dsp_dem which cause the problem but no-one has downloaded that yet.

The settings I am using work well in auto with nudge turned off.

[quote=“Noircogi”]It had the exact same problem with everything at defaults btw.

The second log clearly shows the oscillations of dsp_dem which cause the problem but no-one has downloaded that yet.

The settings I am using work well in auto with nudge turned off.[/quote]
Ah, that log does show the problem. I had been looking at the (misleading) first log that does not. Good to know I wasn’t wrong the first time! I believe the plan was to put a lowpass filter in the speed demand anyway.

I recommend leaving your throttle slew at 100, by the way.
We will get a lowpass filter in. Meanwhile, is flying without the nudge ok? I could backport the fix to 2.78 for you if you like.

Yes, I have nudge turned off and THR_BYP_STAB on for now and everything is fine.

Auto mode works great.

The reason I made the changes I did from defaults was in an attempt to solve the problem. As I remember with defaults, the motor oscillation was about twice as fast at around 2Hz instead of around 1 Hz in the video above. Turning slew down that much just makes it use less throttle range. Since my motor can use 70+ amps at full it was crushing my range at 100. I will turn it back up to 100 since I don’t think it will hurt anything with nudge off and stab bypass on.

I even tried turning slew rate down even more to around 10 but it still oscillated and caused big airspeed swings.

So, I reset most of the above to defaults and set slew-rate to 100 and it was an absolute disaster.

The pulsing is back with a vengeance even with nudge disabled.

The attached log is a section of a short auto flight. Most of it is straight and level between two waypoints.
I have on-board video from this section and you can clearly hear the “siren” sound from the engine oscillating.

The throttle pulsing is clearly visible in the log, but even worse it causes some sort of issue where altitude and throttle diverge wider and wider until the system finally hits THR_MAX which damps things down a bit. Even while at THR_MAX you can see pulsing of the same frequency on the altitude graph.

I’m going back to my old settings but I’m concerned about the stability of the system as a whole now. I believe my tightly constrained slew-rate from before was probably damping things out and hiding the larger problem.

There really seems to be some sort of un-damped oscillation in the TECS system to me.

[quote=“Noircogi”]So, I reset most of the above to defaults and set slew-rate to 100 and it was an absolute disaster.

The pulsing is back with a vengeance even with nudge disabled.

The attached log is a section of a short auto flight. Most of it is straight and level between two waypoints.
I have on-board video from this section and you can clearly hear the “siren” sound from the engine oscillating.

The throttle pulsing is clearly visible in the log, but even worse it causes some sort of issue where altitude and throttle diverge wider and wider until the system finally hits THR_MAX which damps things down a bit. Even while at THR_MAX you can see pulsing of the same frequency on the altitude graph.

I’m going back to my old settings but I’m concerned about the stability of the system as a whole now. I believe my tightly constrained slew-rate from before was probably damping things out and hiding the larger problem.

There really seems to be some sort of un-damped oscillation in the TECS system to me.[/quote]

Certainly not having any trouble of this sort here. You’re probably way overpowered… Did you take the measurements in the tuning guide? Particularly climb rate at full throttle vs sink rate at the same airspeed. They’re meant to measure the power output of your motor.