Paramotor TECS Oscillation Tuning

About

A flight was conducted with a Paramotor which has the following characteristics:

  1. There’s one main motor
  2. There’s two Brake inputs (left and right) via Servo
    3. Pitch control is disabled (Pitch setpoint doesn’t get tracked)
    4. There is no Airspeed Sensor enabled.

The reason for disabling pitch control (via setting PID values to 0) because Parafoils’ pitch angle is physically determined via thrust force & parafoil connection line lengths (exception: Dynamic movements where momentarily pitch changes from symmetric brake input). And it can’t always achieve desired pitch angle (climb up / dive) like Fixed Wing vehicles via brake / throttle input, and is severely limited.

TECS Oscillation problem

It was observed that as soon as vehicle enters Altitude mode (Using TECS), it immediately lowers throttle, dives and gains airspeed, then goes high throttle and goes up, and it continues oscillating.

Further analysis of the log showed that Specific Total Energy Rate is not getting tracked (upper right curve), as well as the Height Rate (Second from the top on the Right)

And as a result, the altitude curve shows oscillating profile (Third from the top on the Right), which isn’t so ideal.

Here’s the log:
https://logs.px4.io/plot_app?log=b3e5e78f-b071-4a1d-ba21-849ee2b61062

Possible Causes

There are multiple factors, but I think these are the most critical ones affecting this behavior:

  1. No Airspeed sensor → TECS behaves a bit differently when there’s no Airspeed data available
  2. No Pitch control → As all pitch setpoints are being ignored, but TECS isn’t aware of this
  3. TECS wasn’t tuned yet (Damping ratio, etc more detailed below)

Possible Solution

I think the only viable solution is to set FW_T_THR_DAMP to “lower” value (0.1 → 0.05).

Contrary to the parameter description: “Increase to add damping to correct for oscillations in speed and height.”, it seems that the higher the damping gain parameter, more aggressive the throttle output will be (e.g. As a P-gain to the Total Energy Rate error), so I thought with oscillation, it could be reduced via reducing the damping gain.

Regarding other possible solutions such as changing FW_T_I_GAIN_THR, it seems that integrator throttle control is disabled when there’s no airspeed sensor.

Initial Dive analysis (Filtered Velocity, etc)

I suspect that vehicle always starts diving in the beginning because as there’s no airspeed sensor, the “Filtered Velocity” simply a first-order curve approaching the Trim speed, and:

1.Initially the filtered velocity starts at 0.0
2. Then it puts Specific Kinetic Energy Rate estimate to a high value (V_filt * d(V_filt)/dt)
3. Which makes the Estimated Total Energy rate at lower value than it is actually (As vehicle isn’t actually increasing velocity), in the log e.g. at 15.0
4. The Control Error becomes big negative value (As current estimated Total Energy Rate is too high), leading to low throttle
5. Leads to vehicle losing speed and diving, as the throttle is too low

Question

Would setting FW_T_THR_DAMP to “lower” value (0.1 → 0.05) be an adequate solution to this issue, or would there be any other solutions? (Other than adding Airspeed sensor)

@sfuhrer would appreciate your input on this!

Other

In general, I found the TECS tuning a bit tricky & not so well documented, as also mentioned in this post:

So I wanted to create this post, hoping to give a bit of clarify in case someone else also gets into a similar situation!

1 Like

Yes I would definitely lower the damping, I’ve done that by now also in the defaults: TECS throttle gains default reduction and transition values from previous PX4 version by sfuhrer · Pull Request #22548 · PX4/PX4-Autopilot · GitHub. On many platforms I have it even completely disabled (in your case maybe not good as it’s your only source of feedback control for the energy states).

For your far-from-nomial TECS usage I would focus on getting the throttle prediction accurate, see Fixed-wing Altitude/Position Controller Tuning | PX4 Guide (main). So the throttle trim, min, max, then climb max, sink min, sink max.
And then I would first de-tune the controller by setting a large FW_T_ALT_TC and check that it doesn’t over-react to gentle height rate setpoints with this large time constant (e.g. 15).

1 Like