Cube O+/PX4 v1.14.0 erroneous pitch/roll setpoint in autonomous mode

First, thank you all for your time. Second, I hope that someone help me with an issue that I’m seeing that has me stumped. I have now recreated this issue on 3 airframes and two Cube Orange+ flight computers.

The issue I’m seeing is that when the vehicle is switch from a “manual mode” (e.g. stabilized) to an autonomous mode (e.g. loiter), the flight controller is sending very large and erroneous pitch and roll setpoints. Below are the events that have happened.

After the Opterra flight we re-accomplished all of the calibrations and tried to recreated the issue again, but weren’t able to. Separately we also used a different Cube O+ on a Rascal fixed wing aircraft to try to recreate the issue, but weren’t able to. We assumed the original issue must have been bad calibrations, and moved on. Then on Friday (24Nov23) we flew the Rascal again and the issue returned, this time also resulting in a crash:

I’m happy to provide any additional information you need.

I sincerely hope you can help with the issues we are seeing. PX4 has been a great resource for us, but these issues with the Cube Orange+ and v1.14.0 are hurting our confidence for continuing to conduct research.

Sorry to hear about your crashes.

I had a look at the logs and tried to make sense of what I see:

28Oct23

You switch to mission but then immediately after to Manual, presumably because the sticks are moved which triggers Manual. Any idea whether and why this taking over happened?

03Nov23

In this flight I don’t see you switch to Loiter ever. Instead you switch to Manual a couple of times and back to Stabilized? Or what am I missing?

24Nov23

I see that the geofence was breached which apparently is not detected or acted upon in Stabilized mode but only once you switch to Loiter.

You have set the geofence action to RTL, but it seems like it stays in loiter a few seconds until going to RTL.

Julian, thank you for your quick response.

I’ll try to help clear up some confusion. I was generally referring to “manual” modes as modes where the pilot still has control (e.g. manual, stabilized, acro, etc.) and “autonomous” modes as those where the pilot is out of the loop (loiter, mission, etc.)

28Oct23 flight: I flew in Stabilized mode and then switched to Mission mode via the RC controller. As soon as I switched to Mission mode (~6:20) the aircraft abruptly pitched/rolled toward the ground. At this point I quickly switched to Manual mode to recover, but did not have enough altitude.

03Nov23 flight: The switch to Hold/Loiter mode (via the GCS) was very brief at ~2:25 to see if we could recreate the issue, which we did. The rest of the flight was done in Stabilized/Manual mode with no issues.

24Nov23 flight: The Geofence Failsafe Trigger was set to Return Mode. The Return to Launch Settings were “Loiter and Land after 120s”. The pilot did not initiate the mode switch to Loiter…it was triggered by the geofence breach. In the logs it looks like the geofence breach preceded the switch to Loiter, but they happened simultaneously and automatically.

Our suspicion is that the issue lies in the TECS or the FixedWingPositionController. We have not seen this issue in v1.13.

Hi @C_G @JulianOes

I’m interested in helping you address the root cause because I’m about to test the Cube Orange+ on my VTOL. I had no idea what happened or why, but I was aware that some setup could accelerate the situation into a catastrophic failure.

Regarding the Flying Wing log file, I found that the vibration is quite high, it might have come from the airframe or inappropriate tuning of PID controller gain and cutoff frequency.

Regarding the PID controller gain, is the UAV well-tuned?

No airspeed sensor installed onboard, why? I experienced flying UAV in high wind and the overall performance is not quite good if no airspeed sensor.

Better reduce the limit of these parameters? after you prove that it all works, try to increase it again as needed.
FW_P_LIM_MAX, 30.0 → 20
FW_P_LIM_MIN, -30.0 → -15
FW_R_LIM, 50.0 → 40
FW_R_RMAX, 70.0 → 55

Have you tried to fly the UAV in Altitude and Position before? What about its behaviors?

I also looked at the flight log of fixed-wing v1.14 here [v1.14 Release Candidate] - Flight testing & Flight Issues (logs) · Issue #21358 · PX4/PX4-Autopilot · GitHub. But it looked normal, they could fly the UAV.

The attached image shows the pitch angle and pitch rate, it looks so weird that the pitch angle setpoint is a positive sign (FC tried to pitch up) but the pitch rate setpoint is a negative sign (tried to pitch down).

1 Like

@saengphet

Thank you for helping to solve this issue. Can you tell me which specific log you pulled that screenshot from? There are a lot of logs on that link and I couldn’t find that particular one.

@C_G from here

Lol…didn’t realize that was from my own log, sorry. Yes, the conflict between the pitch setpoint sign and pitch rate setpoint sign doesn’t make sense.

To address your other points:

  1. Yes, the vibrations were high on the home-built flying wing (likely due to the Cube being mounted fairly close to a large prop). I thought this might have been the cause, but when the issue was seen on the Opterra flying wing and the Rascal conventional fixed wing, I don’t think vibes are the root cause.

  2. We don’t have an airspeed sensor installed because, using standard Cube Oranges and V1.13, we never had any issues flying in manual or autonomous without one. We planned to incorporate airspeed later, but then encountered this issue.

  3. We felt that the UAVs were well-tuned. I probably should have made this more clear in the initial post, but after the 03Nov23 incident when we re-accomplished the calibration we flew the Opterra and Rascal in several modes (Auto-Takeoff, Stabilized, Mission, Hold, Auto-land) without problem. The logs all looked normal and both aircraft flew fine.

Then we flew the Rascal again on 24Nov23 (hadn’t changed anything since the successful flights) and the issue popped back up resulting in a crash. I’m reluctant to try to “solve” the problem by limiting the pitch and roll parameters because a) we didn’t have to do this with v1.13 and b) from the flight logs the FC isn’t honoring the limits as they currently are anyway.

What’s indeed a bit odd is that the roll setpoint goes to 180 degrees in that log screenshot above. So that wouldn’t be right.

I’m linking this in Discord #fixedwing to check if someone has a hunch.

@JulianOes @saengphet

I sincerely thank you for your help. I am personally at a dead end trying to figure it out, especially since it seems unpredictable (like I said, we had several “checkout” flights where the issue didn’t come back up before this most recent incident).

I’m happy to provide any information that could help (log files, param files, other equipment information, etc.)

@sfuhrer added an issue: v1.14.0 erroneous pitch/roll setpoint in autonomous mode · Issue #22487 · PX4/PX4-Autopilot · GitHub which I should have done a while ago :see_no_evil:

Yes I was made aware of this issue yesterday and am currently debugging it. What I see so far points towards an issue in/interfacing with the altitude/airspeed controller (TECS).
Symptoms:

  • pitch setpoint is at -5 rad (which is the default min pitch of TECS) → it seems that it was not updated with the correct min pitch as set on this airframe
  • airspeed_filtered is updated even though we don’t have any airspeed sensor input into the filter
  • TECS goes into “underspeed mode”, even though that should only be possible when an airspeed sensor is present
2 Likes

@sfuhrer This is great news that you are debugging. Please let me know if there is any information that I can provide to help out.

I have found the root caus(es) and propose a fix, see Fix TECS init when switching into a altitude controlled mode only once in air by sfuhrer · Pull Request #22499 · PX4/PX4-Autopilot · GitHub.

As usual it was a chain of bugs that lead to the crash, in your case the combination of flying airspeed-less (which is not as well tested as when flying with airspeed), and not switching into any altitude controlled flight mode briefly while still on the ground.

It’s of course very annoying and unfortunate for you @C_G , but thanks to raising it here you helped us finding quite a few hidden issues and enabled us to patch them, so thanks in that sense! Would you be able to testfly the change (Fix TECS init when switching into a altitude controlled mode only once in air by sfuhrer · Pull Request #22500 · PX4/PX4-Autopilot · GitHub is what I propose to put into 1.14)?

Absolutely…I would be happy to contribute to the community. Thank you again for working on this fix so quickly.

If you don’t mind, I’ll follow up to see what steps I should try exactly that would re-create this issue if it were still there (i.e. do I need to NOT switch to an altitude controlled mode while on the ground).

@C_G We’ve merged the fix into the release 1.14. In case you want to test that version. I can also send you a built binary if you can’t build PX4 yourself.

@sfuhrer Learning to build PX4 myself is on my growing to-do list. In the meantime could you send the binary?

Also, please let me know if there are any specific test steps I should take or avoid to see if the fix works.

Thank you again.

@sfuhrer sounds like we should probably cut v1.14.1!

1 Like

Here is the binary, I hope it’s the right one! Fix TECS init when switching into a altitude controlled mode only once in air by sfuhrer · Pull Request #22500 · PX4/PX4-Autopilot · GitHub

@JulianOes yes I would say so too.