How do I get TECS to fly at demanded airspeed

I’m trying to figure out how to maintain airspeed. In test flights, airspeed demand is set correctly and remains flat, but airspeed fluctuates with external factors.

The ultimate goal of this project is this aircraft, but the test flights here are with a simple 3-channel, 1-meter wingspan flying wing (v4.3.5). The challenge is to configure AP to maintain a demanded airspeed regardless of energy input. This use case is relevant to JATO, bungee launch, winch launch, aerotow, gliders in thermals, air-drop (think 1947 X-1) and other situations where AP cannot control thrust.

To simulate this setup, ESC output is a direct passthrough from a channel that has no effect on AP, and the throttle input is constant at 1000 uSec. Since throttle input is not a factor in AP’s computation, I graph battery current as a proxy for thrust. The graphs show a constant spdem at 16 m/s. They also show the airspeed fluctuate with available thrust.

What I want to achieve is the aircraft pitching up to maintain the demanded airspeed until it either slows down to spdem or runs out of its pitch limit. The test AC can climb indefinitely at 80-degree pitch in FBWA (has a very flat-pitch prop), but TECS doesn’t seem to demand anywhere near as much, so airspeed increases instead.

What am I missing?

Log is here:


Key parameters:

# prioritize speed over altitude targets
TECS_SPDWEIGHT,2
# "GilderOnly"
TECS_OPTIONS,1
# throttle input has no effect on target airspeed in auto-throttle modes
THROTTLE_NUDGE,0
# TX channel 16 is a 2-position switch, sends constant 1,000 uSec
RCMAP_THROTTLE,16
# left stick on channel 3 is not an input to AP
RC3_OPTION,0
# ESC is passthrough from the left stick; essentially a manual throttle in any mode including Auto
SERVO3_FUNCTION,142
# source for TECS.spdem
TRIM_ARSPD_CM,1600
# 80 degree pitch up limit; aircraft can sustain this climb angle in FBWA; it has a very flat prop
LIM_PITCH_MAX,8000
LIM_PITCH_MIN,-2500
# these seem to have no observable effect
TECS_PTCH_FF_V0,15
TECS_PTCH_FF_K,-0.06

The test aircraft, here with our newest intern David.

In my opinion, spdem is the demanded airspeed. The sentence therefore seems a bit confusing. It is not clear to me what you actually want ?

Rolf

I want achieved airspeed to match demanded airspeed. I want to achieve this result by controlling pitch, up to pitch limits.

So you want to do this in flight sections with the propulsion motor turned off ?

What you are looking for can be achieved in SOAR mode, you will sacrifice altitude for speed.

SOAR mode works as a sub-mode of CRUISE/FBWB. In this mode, no engine is used and the throttle stick is used to control the speed (precisely by changing pitch and descent rate).

The following parameters are used in SOAR mode.

TECS_PTCH_FF_V0,15
TECS_PTCH_FF_K,-0.06

1 Like

Thank you, @Lano. I assume you’ve used THERMAL mode. I haven’t, so I probably have misconceptions about it. I assumed it had additional features for circling thermals. These features are not helpful to me.

Thank you for explaining that TECS_PITCH_FF_* parameters are relevant only in THERMAL mode. I had missed that from the documentation.

I want to maintain a constant airspeed for the entire duration of the flight.

Here’s one of the target aircraft. It’s a Skywalker X-8 converted to rocket power. It’s a solid rocket; once you light it, you have no control over thrust.

In case this aircraft looks too exotic, consider numerous FAI free-flight classes where you have no control over thrust once you start it:

  • F1B: rubber, motor limited to 30 grams
  • F1C: internal combustion, motor limited to 5 seconds by external device
  • F1K: CO2, tank limited to 2cc
  • F1Q: electric, energy limited to 3 joules per gram by external device
  • S4: rocket glider (free flight)
  • S8: rocket glider (R/C)

The aircraft in the logs is a testbed. It’s easier to get repeatable flights with an electric motor. I’m using an electric motor that’s physically connected to the same battery as AP, but the RPM is not under AP control.

SOAR is one thing and THERMAL is another. THERMAL is a submode of SOAR; you can use SOAR without THERMAL.

SOAR is gliding taking advantage of altitude loss to maintain speed. As long as you have altitude you can maintain the speed you are looking for.

THERMAL uses updrafts to gain altitude and then exploits that altitude through SOAR.

Thank you, @Lano. I’m reading Soaring — Plane documentation
At first glance, it appears that SOAR is available in auto modes only, when the aircraft is flying a mission. By contrast, THERMAL is a mode (24) the pilot can request same as any other flight mode, while SOAR is not. This is the source of my confusion. Is there a way to switch into SOAR outside a mission, e.g., from FBWA?

With such a complexity a solution via LUA script should be the easiest.

After firing a rocket motor, the script could specify a steep pitch angle until the minimum speed is reached and then lower the pitch angle further and further to maintain the minimum speed.

Interesting project
Rolf

Thank you.

No complexity at all. As a software engineer, I try to avoid the complexity of special cases. I have a way to define this problem very simply, without needing to know anything about rockets or different stages of flight:

Fly an airspeed.

My assumption has been that AP can achieve this by controlling pitch. If my assumption is wrong, I can write a Lua speed-to-pitch controller. It would be easiest to override elevator input in FBWA mode as a function of the error from demanded to measured airspeed. (Elevator input in FBWA directly translates to pitch demand.) But before I start reinventing the wheel, I want to see if this functionality is already available in stock AP.

Ari.

1 Like

TECS_PTCH_FF_V0 and TECS_PTCH_FF_K are ignored because the is is_gliding flag is not set. This flag is set when soaring is active, as others have discussed, but it can be activated at all times by setting THR_MAX to zero.

I personally find it very helpful to study the TECS code when trying to solve these kinds of issues. In this case, the _update_pitch() function governs most of this behavior.

Thank you, @BenWolsieffer. This looks like the answer to my question! It’s raining today, but I’ll report back when the weather improves.

AP is a big, organically grown code base. I get lost in it sometimes. It takes someone who understands it well to point me in the right direction. Thank you for pointing me in the right direction.

As long as I have you here, _flags.is_gliding is a disjunction of three terms:

_flags.gliding_requested || _flags.propulsion_failed || aparm.throttle_max==0

aparm.throttle_max is a parameter. I’m curious about the other two. I can’t immediately see any code that sets them.

ari@deb-xps:~/ardupilot$ grep -r gliding_requested .
./libraries/AP_Soaring/AP_Soaring.cpp:    _tecs.set_gliding_requested_flag(suppressed);
./libraries/AP_TECS/AP_TECS.cpp:    _flags.is_gliding = _flags.gliding_requested || _flags.propulsion_failed || aparm.throttle_max==0;
./libraries/AP_TECS/AP_TECS.h:    void set_gliding_requested_flag(bool gliding_requested) {
./libraries/AP_TECS/AP_TECS.h:        _flags.gliding_requested = gliding_requested;
./libraries/AP_TECS/AP_TECS.h:        bool gliding_requested:1;
ari@deb-xps:~/ardupilot$ grep -r propulsion_failed .
./libraries/AP_TECS/AP_TECS.cpp:    _flags.is_gliding = _flags.gliding_requested || _flags.propulsion_failed || aparm.throttle_max==0;
./libraries/AP_TECS/AP_TECS.h:    void set_propulsion_failed_flag(bool propulsion_failed) {
./libraries/AP_TECS/AP_TECS.h:        _flags.propulsion_failed = propulsion_failed;
./libraries/AP_TECS/AP_TECS.h:        bool propulsion_failed:1;

Ari.

Oh, wait, gliding_requested is set in the first grep match in Soaring.cpp. But propulsion_failed?

Yeah, as far as I can tell propulsion_failed is not used.

1 Like
  1. If modes AUTO, FBWB or CRUISE are entered, and Soaring is enabled…
1 Like

@BenWolsieffer beautiful weather this morning. I’m afraid we were unable to achieve what we wanted with THR_MAX=0, at least not yet.

Log here: https://github.com/arikrupnik/ardupilot-config/blob/master/logs/FIXED_WING/17/2023-05-15%2008-04-22.THMAX-0.bin

RTL shows a flat speed demand but actual speed fluctuating with current.

FBWB shows spdem fluctuating in the range ARPD_FBW_MIN…ARSPD_FBW_MAX (15…25 m/s)* but airspeed never catching up to it except at mid power.