Closed tecnic08 closed 3 months ago
In your logs I see you're on a branch named VTOL-1.8.1-RangeLander
, but the commit isn't in PX4/master. For reference what's the closest commit?
In your logs I see you're on a branch named
VTOL-1.8.1-RangeLander
, but the commit isn't in PX4/master. For reference what's the closest commit?
It is a slight modification from tag v1.8.1
Also, I have found this commit quite suspicious. https://github.com/PX4/Firmware/commit/ea3586cfd96c74d53ba1eedaf7dbd75bfa788afa
In that commit, _thrust_transition
has been removed from the update_transition_state()
in tailsitter.cpp
. However, if you check below on line 337 in the committed files. _thrust_transition
is still being used in waiting_on_tecs()
and it will be used without any value assignment except its initialization value of 0 (zero) in line 171 of vtol_type.h
which is float _thrust_transition = 0.0f;
I have tried changing it to some value and will conduct a bench test tomorrow.
How to solve it?
I guess I encountered the same problem in my plane, which is a standard vtol, when the plane finished front transition, plane has an unexpected pitch down, with throttle drops(not the main cause), then height drops. Please check this issue. https://github.com/PX4/Firmware/issues/11467
There are 2 problem that lead to this throttle drops problem.
1. Waiting for TECS
After transition is completed, TECS of fixed wing controller is not yet publishing information. waiting_on_tecs()
will be called. Which will assign thrust value of _thrust_transition = 0.0f
to the system (in tailsitter). Thus, throttle will drop to zero. Solution is to set _thrust_transition = 0.0f
to some value. Which for our case, we set it to the last know thrust before entering transition mode _thrust_transition = _v_att_sp->thrust;
That fixed half the problem, the other problem with waiting_on_tecs()
is that it will only be called the first time you transition. If you landed the aircraft, take off, and transition again: waiting_on_tecs()
will never be called again. This is the problem with _tecs_running
flag that was never get reset. So, we reset the _tecs_running
flag in update_transition_state()
2. Overshoot after transition If user set forward transition thrust parameter too high, aircraft height will be overshot after transition. Which is over the altitude target (set point). Firmware will reduce the motor to descend. After the transition, aircraft is still slow, and thrust is reduced. Aircraft will stall and fall. This is fixed by reducing the forward transition thrust, to the point where the aircraft will not overshoot. Another solution that we have done is introducing a parameter that limit the descend rate after transition. Firmware will not just drop the throttle after transition to converge with altitude set point.
These discovery and solution were mostly done by my colleague. We will discuss and might submit a pull request to fix this problem.
@RomanBapst sounds like this is not resolved.
I think I've found the root cause and how to fix.
Throttle drop are due to the TECS recognizing that the aircraft has higher altitude than the target altitude and TECS checks that the aircraft has enough airspeed for gliding. So TECS module commanded the aircraft to drop the thrust to glide down to the target altitude. If this was a fixed-wing aircraft, I think it should be fine although it sounds dangerous to me to just reduce the thrust to zero. In my case, it is a tailsitter VTOL which just completed a transition which overshot the target altitude. TECS then ordered the aircraft to drops throttle and lead to my tailsitter becoming uncontrollable.
I fixed by introducing an additional code and parameters. This code limits the sink rate of my aircraft. It will not allow an aircraft to descend too fast. Thus, does not let the thrust suddenly drop to zero.
This issue has been automatically marked as stale because it has not had recent activity. Thank you for your contributions.
It will not allow an aircraft to descend too fast.
Is this also possible with a param?
FYI @sfuhrer
This issue has been automatically marked as stale because it has not had recent activity. Thank you for your contributions.
quad tailsitter drops the throttle to zero which is really bad idea for no control surface quadtailsitter
@julianoes @sfuhrer @tecnic08 please tell me how to address this problem?
@khikmatovfarkhod I'm currently addressing throttle spikes around transitions for tailsitters in https://github.com/PX4/PX4-Autopilot/pull/23033. Let's close this old one here. If you see something else than I address in https://github.com/PX4/PX4-Autopilot/pull/23033 then please open a new issue. Thanks!
Describe the bug Throttle output thrust drop to 0 (zero) after forward FW transition is completed in any mode that has auto throttle control. This happens randomly, some flight does, some flight don't. Same configuration, same aircraft, same location.
Right after forward transition, the aircraft dropped throttle output from forward transition throttle value to zero as shown on the log below. https://logs.px4.io/plot_app?log=5f2f02c7-d2bd-4ff3-9d10-c48c87272d2f
This behavior also occurred in any other mode that has auto throttle control (Altitude, Position) but does not always occur on every flight. The log below is the flight without this behavior. https://logs.px4.io/plot_app?log=4eed6594-9aaf-4026-a571-202857b4c387
Besides the above log which is from an actual flight test, we also conducted bench test in position mode to reproduce this behavior. The throttle drop also occurred in the same way as the actual flight test. The logs from bench test are presented below.
To Reproduce Steps to reproduce the behavior (on bench-test):
Expected behavior Throttle should not drop to zero and causing it to be uncontrollable.
Log Files and Screenshots First figure (throttle drop): https://logs.px4.io/plot_app?log=5f2f02c7-d2bd-4ff3-9d10-c48c87272d2f 2nd figure (throttle not drop): https://logs.px4.io/plot_app?log=4eed6594-9aaf-4026-a571-202857b4c387 Bench-test attempt Attempt1: https://logs.px4.io/plot_app?log=cade9885-e8c0-48e0-a730-1658fb1c69c4 Attempt2: https://logs.px4.io/plot_app?log=e38fdf1f-58cd-4fd9-8ce1-a964cee2b72e Attempt3: https://logs.px4.io/plot_app?log=2ac76818-9c41-4b5e-b865-1a74b5623578 Attempt4: https://logs.px4.io/plot_app?log=fe89ef0b-9b6d-4473-8810-911d028d638d Attempt5 (w/o drop) : https://logs.px4.io/plot_app?log=ebd3c67a-2ebf-4028-ac8d-216dc5e25822
Drone: Airframe config: Duo Tailsitter