I’m seeking assistance with a crash issue on a fixed-wing plane running v1.14. The plane stalled and crashed during an auto-launch, despite previous successful launches. The incident seems to involve a potential issue with the TECSControl::_calcPitchControl
function.
Observation: During takeoff, our pitch setpoint was initially 10 degrees, aligning with FW_TKO_PITCH_MIN
. Unexpectedly, the setpoint increased to 15 degrees (FW_P_LIM_MAX
), causing excessive pitching. This occurred before reaching adequate airspeed, leading to a stall and crash.
Potential Issue: Upon examining TECSControl::_calcPitchControl
, I noticed the logic might inadvertently cause such setpoint jumps. The code snippet below suggests the pitch setpoint is constrained between current, max, or min values, which might explain the sudden increase from 10 to 15 degrees.
const float pitch_increment = dt * param.vert_accel_limit / math::max(input.tas, FLT_EPSILON);
_pitch_setpoint = constrain(pitch_setpoint, _pitch_setpoint - pitch_increment,
_pitch_setpoint + pitch_increment);
Is this behavior by design, or could it be a bug? Am I focusing on the correct part of the code, or is this a diversion from the actual issue?
Can you share other telemetry? Also any config chanegs?
It could be related to this:
PX4:main
← PX4:pr-fix-tecs-init-main
opened 12:55PM - 07 Dec 23 UTC
### Solved Problem
Fixes https://github.com/PX4/PX4-Autopilot/issues/22487 resp… . https://discuss.px4.io/t/cube-o-px4-v1-14-0-erroneous-pitch-roll-setpoint-in-autonomous-mode/35557/11
The issue is only noticeable when the vehicle is switched into an altitude controlled mode when already in air, and there is no airspeed sensor connected. Then the airspeed state is 0, which leads to a division by 0 while calculating the pitch setpoint in TECS. And TECS initializes wrongly and constrains the INF only to a large value of 5rad.
It is NOT observable if at any time before takeoff the flight mode was already in an altitude controlled mode for a bit, then TECS is correctly initialized by the time it is actually needed.
### Solution
ac33e4eca11ed is the real fix. Prior to this commit, the `_control_params`, eg. `_control_param.pitch_max` , are already used in `TECS::initialize() `but not initialized with the actual settings on the vehicle. As the default for the pitch min/max is 5rad the effect is then clearly noticeable.
e177e9a07b is patching the airspeed-less handling, which is further robustified with 4a8f346d and 09648310. Without these changes, the .tas state is at 0 which then leads to a division by 0, and due to the wrong pitch limits it doesn't get constrained properly.
The other commits are not directly related to the crash, but proposals for mini clean ups and further guards.
### Changelog Entry
For release notes:
```
Bugfix: Correct TECS initialization when switching into an altitude controlled mode only once in air
```
### Alternatives
### Test coverage
SITL testing. The issue is reproducible in SITL. As the SITL though inits in Position mode, there is a small hack needed to not have it run TECS::update() before switching into Stabilized mode: do not run it within 10s of boot --> `if (_local_pos_sub.update(&_local_pos) && _local_pos.timestamp > 10_s) `. Further one has to disable the airspeed sensor, I did that by commenting out the publishing of the simulated differential_pressure topic in SimulatorMavlink.
With current main:
![image](https://github.com/PX4/PX4-Autopilot/assets/26798987/93a6dc0f-ddc4-4c30-b2fb-e092eb57f8df)
With this PR:
![image](https://github.com/PX4/PX4-Autopilot/assets/26798987/7ffc9904-4e2a-446b-9a83-7a3f65a50a2d)
Are you using v1.14.0 or later? (It was patched into v1.14.1 I believe)
If you have a log please share it!