TKOFF_THR_SLEW and THR_SLEWRATE not working

I finally got around to trying to hand launch my clouds today. One good, one (very) bad launch. But, I believe I have a good idea why my launch failed…so I’m not asking about that.

While looking at the logs for my good launch and my bad launch, I noticed that in both cases the motors are going from zero throttle to full throttle in 40 milliseconds. I set the TKOFF_THR_SLEW vale to 33, expecting the ramp from zero to full to take 3 seconds. Here’s a graph showing CTUN’s throttle request, closely followed by the PPM output signal to the ESC. I also have shown the RC channel in (3) for throttle, which is at 1000 (no manual throttle input to “nudge” the throttle output).

Log is available at https://drive.google.com/open?id=17KzN1Y6NTf0d9JFLikY8eaWsuh-uml2n

I also flew another plane running 3.9.5 beta code. From looking at the auto launch sequence for the other launch, I can see that CTUN throttle request is almost immediate, but that the PPM output (on channel 2 in this case) properly ramps up the speed to the ESC over a one second period. I.e., this version appears to work properly.

RR

I upgraded my Pixhawk clone to 3.9.5. This did not resolve the problem, throttle still advances in a fraction of a second regarless of TKOFF_THR_SLEW.

I compared all the takeoff parameters between the plane that works (running 3.9.5 beta 2) and the plane where it fails. There were a few differences:

  1. The one that failed had TKOFF_THR_MAX set at 100 and the one that worked had 0. Making TKOFF_THR_MAX zero (and hence using the normal THR_MAX) did not help.

  2. The plane that failed had TKOFF_THR_SLEW at 33, the one that slewed slowly had it set at zero (meaning that it used the normal THR_SLEWRATE, set at 120). Doing the same on the plane that refuses to slowly ramp the throttle, made no difference…it still ramps the throttle in ~40 ms.

The only remaining obvious difference is that the failing plane uses a PixHawk clone and the properly ramping plane uses a Matek F405 Wing.

But the latest results show that the title of this thread is incomplete. Throttle slew limiting isn’t working at all, the takeoff case is just one instance of that.

RR

@RogerR sorry, the 3.9.5 release did not include the fix to make dual-motor setups use throttle slew on the motors. It does work for single motor setups, and the fix is in master.
I’ve now added that fix ready for 3.9.6, and I’ve put a pre-built binary for the Pixhawk1 here for you to test:
http://uav.tridgell.net/RogerR/plane-3.9.5-dual-motor-slew.apj
Cheers, Tridge

Thanks for looking at this and sending the binary!

I just loaded it. I get this version data in the messages:
Pixhawk1 003C0028 30365119 31313731
ChibiOS: d2030d88
ArduPlane V3.9.5 (1a56659e)

However, there’s no apparent change in behavior. I set the slew rate for takeoff and normal throttle both to 20 (which should ramp up over 5 seconds) and this was the result (3 and 6 are my throttle channels:

Log is at https://drive.google.com/open?id=1qtYQY2FoO7sTHC-I84O_qGW28A88hCAY

RR

you’re right, sorry, I stuffed up the patch
here is a new version to test:
http://uav.tridgell.net/RogerR/plane-3.9.5-dual-motor-slew-test2.apj
Cheers, Tridge

1 Like

Tridge,

No problem. IMHO, the new version works properly.

In the spirit of testing it completely, I also initiated some yaw to validate that differential thrust still works OK. You can see differential throttle (albeit at a fairly modest amount) after the first throttle peak ends (visible just past 14:16:38 with throttle around 1350-1400 and around 14:16:48 with throttle at full).

I also tested with TKOFF_THR_SLEW at 25 and THR_SLEWRATE at 125 (which I will actually use). The behavior looks correct. 4 second ramp on auto takeoff, ~.8 seconds for ramp up and ramp down from manual throttle actuation. My motors sound much happier when shutting off with a non-zero ramp value!

Thanks again!

RR

2 Likes

great, thanks for testing!

Tridge,

When testing with long slew rates, it occurred to me that it might make sense, as an enhancement, to allow the throttle to slew (THR_SLEWRATE) faster than the present limit of 127 (8/10ths of a second).

I can imagine wanting to kill throttle (during a failed takeoff) or raise the throttle more quickly (during a stall) while still retaining some slew moderation. Personally, I’d probably pick something more like 4 tenths of a second if it were available.

A wider range could still fit into 7 bits of parameter resolution if allowing an 8 bit field is difficult. I doubt that anyone has ever intentionally used the values of 1, 2, 3, 4. A few of those could be re-purposed if need be.

RR

yes, the current limit is actually given by the loop rate. It can’t do less than 1 microsecond per loop with the current design due to integer rounding.
I’d like to redo it to use a float, so it can do arbitrary speeds

Tridge,

One more thought on slew rates.

The slew rate for auto takeoff only applies when advancing the throttles. No issue there.

The slew rate for general throttle control works in both directions. Up and down. It seems that the slew rate limit on retarding the throttle could be a safety issue.

My desire for a quicker THR_SLEWRATE was primarily due to not wanting the props to thrash the ground for an extended period after a failed takeoff. But, the far worse risk is having the props thrash someone who happens to occupy the same space as the plane…and having that painful event continue for a second or more during the slew back to zero throttle.

Perhaps it would make sense to offer asymmetry, with a advancing and a retarding slew rate, so that the shutoff could be made faster?

RR

This problem was repeated in the variant of Plan 4.1

my post: TKOFF_THR_SLEW not respected in auto takeoff

Suggestion?