Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Pixracer + S.Bus = Failsafe not working properly => fly away #5357

Closed
anton-matosov opened this issue Aug 20, 2016 · 28 comments
Closed

Pixracer + S.Bus = Failsafe not working properly => fly away #5357

anton-matosov opened this issue Aug 20, 2016 · 28 comments
Assignees

Comments

@anton-matosov
Copy link
Contributor

anton-matosov commented Aug 20, 2016

I have switched to the new FrSky X4R-SB RX (S.Bus) for my Pixracer drone and experience an issue with failsafe mode.
I have set RX failsafe to no pulse and px4 can detect RC signal loss with no problem and triggers failsafe mode on.
However instead of performing failsafe action it just holds the same servo values (even if I move drone).
This behavior is very dangerous and can result in fly away.

pastedgraphic-1

P.S.
I was using Orange RX with CPPM protocol previously and all worked perfectly fine with it. On signal loss px4 was simply turning off all PWM outputs (as it has no GPS and can't RTL/loiter/land) which is acceptable behavior for racing drone.

P.P.S.
I use 1.4.1 Release

@LorenzMeier
Copy link
Member

@kd0aij Could you look into this? Very likely the FMU driver doesn't set the failsafe state correctly.

@anton-matosov
Copy link
Contributor Author

@kd0aij please let me know if you need any logs or help with that.

@anton-matosov
Copy link
Contributor Author

Just in case sess161.zip

@anton-matosov
Copy link
Contributor Author

Somewhat related issue from long time ago ArduPilot/ardupilot#645

@anton-matosov
Copy link
Contributor Author

I have found the root cause of the problem.
Position estimator was set to local_position_estimator. In this mode failsafe doesn't work
Resetting it to position_estimator_inav or ekf2 solves the problem and failsafe changes mode to land on RC signal lost (as configured)

@kd0aij
Copy link
Contributor

kd0aij commented Aug 21, 2016

@jgoppert That's confusing, since the commander module (not the position estimator) should be managing failsafe.
@anton-matosov Your log shows the system entering "termination" state 0.75 seconds after RC.lost is asserted.
But my initial look at the source indicates that state is only implemented by fw_att_control...

@kd0aij
Copy link
Contributor

kd0aij commented Aug 21, 2016

This issue seems to be related to #4344, but there are many unanswered questions (of mine) there, and no indication that there was any successful testing.
@jgoppert Based on what little knowledge I have about this, I'd guess that control_mode.flag_control_termination_enabled = true;
needs to be acted upon in mc_att_control.

@jgoppert
Copy link
Member

Yeah that is odd. The position estimator shouldn't have any effect on this.

@LorenzMeier
Copy link
Member

LorenzMeier commented Aug 21, 2016

@kd0aij The flag you linked has nothing to do with this. Its for forcing flight termination. I noticed though that this is missing in multicopters, so something we should address in the commander rewrite.

@jgoppert The reason things go bad is probably because you're deriving your own EPH / EPV in LPE instead of forwarding the GPS values. That leads to the state machine in commander thinking you have valid GPS and trying to put the system into GPS failsafe (which doesn't work).

So what we need to do is to introduce a global position valid flag into the vehicle_global_position message and evaluating that in addition to the eph / epv values.

@LorenzMeier
Copy link
Member

Or we might not need a change at all and its some bad initially published values. Needs more inspection.

@anton-matosov
Copy link
Contributor Author

It sounds weird to me either, but I have tried to reproduce it several times. And behavior is 100% stable.
If I have local_pos estimator I see:

  • RC lost
  • failsafe on
  • stays in manual mode and locks PWM outputs

If I switch to inav estimator I see:

  • RC lost
  • failsafe on
  • switch to LAND mode (failsafe action)

So failsafe triggers on in both the cases, but no failsafe action is taken in the first case.
I have also noticed that I have 3 circuit breakers enabled by default on my pixracer: motor failure, flight termination and safety switch.
I am wondering if flight termination circuit breaker should not be on by default.

@kd0aij
Copy link
Contributor

kd0aij commented Aug 21, 2016

@LorenzMeier I said that I had little knowledge about this. And your comment might have explained why something called "flag_control_termination_enabled" is irrelevant to nav state "NAVIGATION_STATE_TERMINATION". It's difficult to reverse engineer code like that.

@jgoppert
Copy link
Member

Lpe won't publish the global position message if it doesn't have any gps or flow, is that the issue?

@anton-matosov
Copy link
Contributor Author

anton-matosov commented Aug 22, 2016

I did some real flight tests and drone really tries to fly away (it was tethered, so I still have it).
I have tried RTL and LAND modes, result of RC loss is unpredictable in either case.

Another observation via QGC is that failsafe triggers LAND mode on RC loss no matter what setting I have in the parameters (loiter, land or RTL). And also when I try to enable LAND mode via QGC it doesn't let me do that which is correct as I don't have GPS.

P.S.
I have found that NAV_RCL_ACT is used as bool, so its values are not respected.
param_t _param_enable_rc_loss = param_find("NAV_RCL_ACT");
param_get(_param_enable_rc_loss, &rc_loss_enabled);
bool nav_state_changed = set_nav_state(&status, ... (rc_loss_enabled > 0), ...);

This is the failsafe logic:

bool set_nav_state(struct vehicle_status_s *status, ...
           const bool rc_loss_enabled, ...)
switch (internal_state->main_state) {
    case commander_state_s::MAIN_STATE_ACRO:
    case commander_state_s::MAIN_STATE_MANUAL:
    case commander_state_s::MAIN_STATE_RATTITUDE:
    case commander_state_s::MAIN_STATE_STAB:
    case commander_state_s::MAIN_STATE_ALTCTL:

        /* require RC for all manual modes */
        if (rc_loss_enabled && (status->rc_signal_lost || status_flags->rc_signal_lost_cmd) && armed) {
            status->failsafe = true;

            if (status_flags->condition_global_position_valid && status_flags->condition_home_position_valid) {
                status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_RCRECOVER;

            } else if (status_flags->condition_local_position_valid) {
                status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LAND;

            } else if (status_flags->condition_local_altitude_valid) {
                status->nav_state = vehicle_status_s::NAVIGATION_STATE_DESCEND;

            } else {
                status->nav_state = vehicle_status_s::NAVIGATION_STATE_TERMINATION;
            }

So it seems that I somehow have valid local position condition_local_position_valid and that's why it triggers autoland NAVIGATION_STATE_AUTO_LAND

@anton-matosov
Copy link
Contributor Author

I have also compared parameters of my previous setup that worked and was terminating flight on RC loss (configured with QGC 2.9.7 dev build)

1   1   CBRK_AIRSPD_CHK 0   6
1   1   CBRK_BUZZER 0   6
1   1   CBRK_ENGINEFAIL 284953  6
1   1   CBRK_GPSFAIL    240024  6
1   1   CBRK_IO_SAFETY  22027   6
1   1   CBRK_NO_VISION  0   6
1   1   CBRK_RATE_CTRL  0   6
1   1   CBRK_SUPPLY_CHK 0   6
1   1   CBRK_USB_CHK    197848  6

and my current parameters (configured with QGC 3.0.0 stable) and here are results:

1   1   CBRK_AIRSPD_CHK 0   6
1   1   CBRK_BUZZER 0   6
1   1   CBRK_ENGINEFAIL 284953  6
1   1   CBRK_FLIGHTTERM 121212  6
1   1   CBRK_GPSFAIL    0   6
1   1   CBRK_IO_SAFETY  22027   6
1   1   CBRK_NO_VISION  0   6
1   1   CBRK_RATE_CTRL  0   6
1   1   CBRK_SUPPLY_CHK 0   6
1   1   CBRK_USB_CHK    197848  6

The difference is that CBRK_GPSFAIL was enabled in previous build, but not in the current one and CBRK_FLIGHTTERM is enabled in the current build. But I have not configured either of them, they are coming as default values. @LorenzMeier I don't feel that these are correct defaults.

@anton-matosov
Copy link
Contributor Author

@LorenzMeier is there a way to configure failsafe to just kill motors instead of RTL or Land as neither of them is possible without GPS (however failsafe still tries to do it).

@mhkabir
Copy link
Member

mhkabir commented Aug 22, 2016

Without GPS it should perform an open loop descent. However, killing the motors should be implemented as an option as well, especially for racers.

@anton-matosov
Copy link
Contributor Author

@mhkabir you are correct, it switches to NAVIGATION_STATE_DESCEND, not NAVIGATION_STATE_AUTO_LAND

@anton-matosov
Copy link
Contributor Author

What does NAVIGATION_STATE_TERMINATION mean? Is it equivalent to kill switch?

@mhkabir
Copy link
Member

mhkabir commented Aug 22, 2016

It's implemented for fixed wing only. Probably be easy to extend the termination state to MC to kill the motors. Just check the kill switch implementation.

@anton-matosov
Copy link
Contributor Author

Ok. I will try to do that.

@anton-matosov
Copy link
Contributor Author

I have performed more in flight testing, but this time indoors. Drone is really switching to NAVIGATION_STATE_DESCEND on RC loss and starts to land (with inav estimator).
The biggest concern here is that landing speed is super slow (I have default landing of 0.5m/s in params) and if it gets any external force on it it stops going done. I think that is the main reason why it was not landing outdoors, because there was pretty strong wind and it was just constantly trying to compensate it and was forgetting to land.
Also I have noticed that if I don't reboot flight controller on the second and any further RC loss it will just turn of motors.

I have also tried to use local pos estimator and drone just locked pwm outputs instead of landing. However logs show that it have switched to NAVIGATION_STATE_DESCEND, but QGC doesn't report that it really starts landing. I bet it might because I have some parameters missing/misconfigured in my setup, so it simply fails somewhere. Although it allows me to fly with this params missing I would prefer to not even arm if it can't perform critical operations like landing with this data missing.

I have collected all the logs and recorded videos of all my tests. If you are interested in them I will upload them.

@kd0aij
Copy link
Contributor

kd0aij commented Aug 24, 2016

This is a plot from the first log you posted showing RC.lost asserted, followed by failsafe and navstate 13 (termination):
rclost

@LorenzMeier
Copy link
Member

Termination needs to be allowed by clearing the circuit breaker for it which defaults to on. Is this the missing step?

@anton-matosov
Copy link
Contributor Author

I will try it out without circuit breaker for termination and see what happens

@julianoes
Copy link
Contributor

Also I have noticed that if I don't reboot flight controller on the second and any further RC loss it will just turn of motors.

This seems like a bug.

I have also tried to use local pos estimator and drone just locked pwm outputs instead of landing. However logs show that it have switched to NAVIGATION_STATE_DESCEND, but QGC doesn't report that it really starts landing. I bet it might because I have some parameters missing/misconfigured in my setup, so it simply fails somewhere. Although it allows me to fly with this params missing I would prefer to not even arm if it can't perform critical operations like landing with this data missing.

I think we need to look at if different valid flags or topics are published for LPE vs. inav when used without GPS.

I will try it out without circuit breaker for termination and see what happens

I don't think termination plays a role here, unless we lose baro as well.

@anton-matosov
Copy link
Contributor Author

I have made a test of LPE with termination circuit breaker off and it behavior is the same.
as per @mhkabir flight termination is implemented only for fixed wing, not MC. All PWM outputs are locked at their last values.

Drone-rodeo-local-estimator.zip
rc loss termination

@anton-matosov
Copy link
Contributor Author

Fixed in #5863

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

6 participants