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

Critical RC Loss Failsafe Bug, Potenial Vehicle Lost #12381

Closed
bozkurthan opened this issue Jul 1, 2019 · 25 comments · Fixed by #13218
Closed

Critical RC Loss Failsafe Bug, Potenial Vehicle Lost #12381

bozkurthan opened this issue Jul 1, 2019 · 25 comments · Fixed by #13218

Comments

@bozkurthan
Copy link
Contributor

Describe the bug
Hello, I'm using PX4 latest Firmware in Pixhawk 2.1 (Cube). Geometry is generic Quadrotor X geometry. My communication system is depending on RF modules(Long range ~900MHz) between Vehicle and RC. I'm feeding Pixhawk RC_IN with RF PPM signal out which is on RC. Radio Controller's (FrSky Taranis X9D) PPM frame length is 22.5 ms and it has 8 channels. Failsafe action was RTL.

Yesterday, I was trying failsafe actions. While I was trying RC Loss failsafe, I just power off RC by manual and failsafe action wasn't triggered. Then, Vehicle just fell down.
I just examined log data. I explored PPM signal didn't cut off by RF.
Screenshot from 2019-07-01 15-28-29

PX4 thought PPM signal wasn't cut off. RF is sending continuously PPM signal which has 12 channels when RX-TX communication is lost. Channels have 1 ms frame length and PPM frame length is 24ms which has to be 22.5ms.

The problem is that RF module sends PPM signal even RC signal is lost. It also send 1ms signal which is meaning lowest signal strength for channels. So, failsafe action isn't triggered by itself which causes vehicle fall.

To Reproduce
Steps to reproduce the behavior:

  1. Drone switched on.
  2. RC switched on.
  3. Took off with any mode.
  4. Cut off RC power.
  5. See error.

Expected behavior
When RC signal lost, failsafe should be triggered independently of RF PPM signal. Also, number of channels and frame length shouldn't be change itself when vehicle is armed.

Log Files and Screenshots
When RC signal is normal.
IMG_20190701_131840

When RC signal is went off.
IMG_20190701_131758

RC frame and channel info.
IMG_20190701_131919

Possible solutions:
For my case, I just changed this line:
https://github.com/PX4/Firmware/blob/528d2f61a0ac30daa100f06de0cc78dcc072e43e/src/modules/sensors/rc_update.cpp#L230
To this:
if (rc_input.rc_lost || rc_input.rc_failsafe || rc_input.channel_count > 8)
It works but I know it is dirty solution.

Solution 1:
We should change line which is constrain value of this message:
https://github.com/PX4/Firmware/blob/cc68775defa8432560bd7bb90a038d9e7c0fa8c9/msg/input_rc.msg#L22
And the number of channel should change by only calibrating RC. When number of channels is changed on armed state, failsafe should be triggered.

Solution 2:
PPM frame length also has constraint value by RC. When PPM frame length changes unexpectedly, failsafe should be triggered.

@hamishwillee
Copy link
Contributor

I think the problem is probably a receiver configuration issue - PX4 cannot trigger a failsafe if it is still getting what looks like a valid PWM signal.

@julianoes this has come up before but docs have not be updated (probably need to update here). Do you know what a receiver should output when the transmitter stops, and how is this configured? - e.g. for the main receivers we support https://docs.px4.io/master/en/getting_started/rc_transmitter_receiver.html#compatible_receivers
If not, who would be best person to ask.
[And of course I am assuming I'm not completely wrong about the cause!]

@julianoes
Copy link
Contributor

Do you know what a receiver should output when the transmitter stops

Best and easiest case is if the receiver stops outputting anything which will be correctly interpreted as RC lost.

An alternative is that the receiver goes into a "failsafe" setting with throttle low. This needs to be configured on the PX4 side using the param https://dev.px4.io/en/advanced/parameter_reference.html#RC_FAILS_THR.

The docs should mention:

  1. These two ways of configuring it.
  2. That every setup needs to be verified for RC lost to check it is detected correctly.

@hamishwillee
Copy link
Contributor

Thanks @julianoes. Useful information, but would be good to see how this works in real receivers.

Consider the X8R receiver for this issue. By default this will just output whatever signal it had before connection was lost. Our option here is to set failsafe as outlined here. This can set the output value to failsafe values based on control positions. That means we can't set a fails throttle to an invalid value, can we? Unless we somehow set the low throttle, then recalibrate the range on the transmitter to another range that we actually use for flying. Or to put it another way - what is best thing to do in this case?

Similarly this one also has a low throttle failsafe

This SBUS one doesn't appear to have a failsafe.

Can you think of any that output "nothing"?

@julianoes
Copy link
Contributor

That means we can't set a fails throttle to an invalid value, can we? Unless we somehow set the low throttle, then recalibrate the range on the transmitter to another range that we actually use for flying. Or to put it another way - what is best thing to do in this case?

What I do is to use the trim (on the RC) to lower throttle all the way. Then I set this as failsafe and reset the trim again.

This SBUS one doesn't appear to have a failsafe.

I think SBUS just stops sending stuff, right?

@dlwalter
Copy link
Contributor

dlwalter commented Jul 3, 2019

I ran into a similar issue with our RFD900 radios - RFDesign's windows GUI tool was not programming the failsafe signal correctly and instead all 12 channels would just output 1000us - which would correspond to low throttle, full roll, roll pitch, and disarm.

https://discuss.px4.io/t/rfd900x-failsafe-ppm-not-programmed-correctly/10364/3

I recommend everyone tests their aircraft behavior in a strapdown test and cut off ground radios to see if it is appropriately detecting an RC loss.

@dlwalter
Copy link
Contributor

dlwalter commented Jul 3, 2019

As opposed to trying to detect an RC cutoff from an incorrectly setup radio Is there a way to maybe include an RC cutoff test procedure in QGC similar to sensor calibration? Have a flag for a radio/aircraft pair that alerts the operator that RC cutoff hasn't been tested?

Or just a parameter and annoying notification like the VT_ROLL_DIR_V19 or whatever that you have to manually set to get the warning off.

@bozkurthan
Copy link
Contributor Author

@dlwalter actually I have same radio. But how we can avoid from this issue. Failsafe test procedure is plausible. But after that there should be some structure for this issue.

An alternative is that the receiver goes into a "failsafe" setting with throttle low. This needs to be configured on the PX4 side using the param https://dev.px4.io/en/advanced/parameter_reference.html#RC_FAILS_THR.

The docs should mention:

  1. These two ways of configuring it.
  2. That every setup needs to be verified for RC lost to check it is detected correctly.

@julianoes RC_FAILS THR for only unreliable PWM output. As @dlwalter mentioned we have valid signal from RFD900. Maybe we can add RC_FAILS_CH_THR (which means threshold for channels) to avoid this issue. Furthermore it should be configurable for RC types (e.g. RFD900 radios send 12 chs and 1000 pwm per ch). When we choose RC type, failsafe scenario can be change by itself. Also, we have type of RC in message system which detected by driver module.

https://github.com/PX4/Firmware/blob/12fcddd288911a32060b7fd2a52c22ab65290535/msg/input_rc.msg#L3-L17

@julianoes
Copy link
Contributor

Ok, so you're suggesting that we add a check like this?

If number of channels == 12 and all channels == 1000 PWM then RC lost -> failsafe?

@bozkurthan
Copy link
Contributor Author

Exactly this is what supposed to be. I can create PR for this. But should we restrict this for only type of RFD900 PPM connection. Is it valid solution?

@julianoes
Copy link
Contributor

I can create PR for this.

I think that would be great.

But should we restrict this for only type of RFD900 PPM connection.

I don't know how we could do that.

Is it valid solution?

I think it's safe because if we accidentally ignore 12 channels at 1000 we ignore "information" that really doesn't tell us anything anyway.

@bozkurthan
Copy link
Contributor Author

Hello @julianoes,

I've just started write down code today to create PR. Firstly, I just added following lines to Firmware/src/modules/sensors/rc_update.cpp module :

/* check failsafe by channel values to detect RC loss (This statement is specific for only RF module that still sending valid PPM signal when RC loss from ground RF) */
if (rc_input.channel_count==12){

       for (unsigned int i = 0; i < 12; i++){
           if (rc_input.values[i]<1000 && rc_input.values[i]<1003){
           signal_lost = true;
           }else{
           signal_lost = false;
           break;
           }
       }
}

These lines provide that when channel number is 12 and values of channels are between 1000 and 1003, failsafe will be triggered. (The values were taken from the log). But when I applied and tried this, I saw that the application doesn't enter the this statement. So, I just wondered that how many channels are counted by logic. I just printed screen and found that 16 channels counted by logic.

When I analyzed log of input_rc I just thought that 12 channels are counted because of channels' values. But actually there was a 4 channels more than I expected. Also, these channels have 0 values. Moreover, I think there is many channels which have 0 values but they aren't counted because of these lines:

https://github.com/PX4/Firmware/blob/528d2f61a0ac30daa100f06de0cc78dcc072e43e/src/modules/sensors/rc_update.cpp#L257-L259

After whole these steps I changed code to following lines and failsafe works well.

/* check failsafe by channel values to detect RC loss (This statement is specific for only RF module that still sending valid PPM signal when RC loss from ground RF) */

if (rc_input.channel_count==16){

       for (unsigned int i = 12; i < 16; i++){
           if (rc_input.values[i]==0){
           signal_lost = true;
           }else{
           signal_lost = false;
           break;
           }
       }
}

Should I create PR with this statement? Thanks :)

@dlwalter
Copy link
Contributor

During fixed wing flight a pilot could concievably send the following command - full yaw left, full roll left, full pitch down, throttle down, (the remaining channels are modes that could be all set to 1000us).

Wouldn't this be a valid flight command (although an edge case) where we would not want the aircraft to trigger a RC failsafe/RTL event?

@bozkurthan
Copy link
Contributor Author

@dlwalter 13-14-15-16 channels have 0 pwm value for this case. I think it can't be valid for any airframe type. I just added failsafe segment of input_rc. Actually, in my opinion number of channels shouldn't be change after rc calibration.

@dlwalter
Copy link
Contributor

Isn't this dependent on the rc controller? I thought the RFD900X is capable of transmitting a 16 channel PPM signal if that's what it is receiving on GPIO1.1 input pin.

@bozkurthan
Copy link
Contributor Author

the remaining channels are modes that could be all set to 1000us

You are right about this. This solution not valid for all airframe and feasibility configuration.
if (rc_input.values[i]<1000 && rc_input.values[i]<1003)

the RFD900X is capable of transmitting a 16 channel PPM signal

I see your point, more field test is needed. I'll try with different channel number and gonna discuss about that.

@bozkurthan
Copy link
Contributor Author

Hello again @dlwalter . I just changed FRSKY configuration from 8 channels 22500ms total frame to 2 different configuration. ( 12 channels 30.5ms total frame and 14 channels 34.500 total frame). I got same log from 12 channels and 14 channels config as 8 channels config when I closed RC manually:

12 Channels:

IMG_20190718_181312

Screenshot from 2019-07-18 18-09-38

14 Channels:

IMG_20190718_181644

Screenshot from 2019-07-18 18-26-11

Furthermore, I agree with you on that not using 1000-1003 failsafe scenario. But I used these following lines in PX4 Flight Stack. It's only active when 12-16 channels' values are 0. I think RFD900 sends always same value.

if (rc_input.channel_count==16){

       for (unsigned int i = 12; i < 16; i++){
           if (rc_input.values[i]==0){
           signal_lost = true;
           }else{
           signal_lost = false;
           break;
           }
       }
}

@bozkurthan
Copy link
Contributor Author

@dlwalter the code fragment that mentioned above is OK in your opinion? If it's ok,I'm ready to create PR for it. FYI, @julianoes .

@julianoes
Copy link
Contributor

I think that's correct but you also want to check the first 12 channels, right? Don't they also go to some failsafe setting?

@bozkurthan
Copy link
Contributor Author

@julianoes they are going but there is a problem with their values which is mentioned before by @dlwalter .

During fixed wing flight a pilot could concievably send the following command - full yaw left, full roll left, full pitch down, throttle down, (the remaining channels are modes that could be all set to 1000us).

So if I add following lines it can be valid to decline wrong failsafe trigger for fixedwing case:

//This case only for RFD modules which produce PPM signal
if (rc_input.channel_count==16){
       for (unsigned int i = 0; i < 16; i++){
           if (i <12 && rc_input.values[i]<1000 && rc_input.values[i]<1003){
           signal_lost = true;
           }else if  (rc_input.values[i]==0){
           signal_lost = true;
           }else{
           signal_lost = false;
           break;
           }
       }
}

But this increases time complexity. If it seems normal to you, I'll create PR. We can discuss and take review on PR.

@mcsauder
Copy link
Contributor

Oh man, if someone goes to the trouble to do all of that, it must certainly be intentional and should also be acted upon... I have been flying rc for 3 decades now and can state with certainty that those signal commands do no happen by accident.

@julianoes
Copy link
Contributor

Ok @bozkurthan I think that check is good.

@bozkurthan
Copy link
Contributor Author

Hello @julianoes and @hamishwillee I couldn't be able to merge #12595 . Also, I think PR isn't good solution for this case. If you think the solution is enough to prevent this case, I'll try reopen PR with new branch.
@hamishwillee , Is #575 solution for this? I want to close this issue and PR.

@hamishwillee
Copy link
Contributor

@bozkurthan I don't know - mostly I'm a tech author. Deferring to others.

@julianoes
Copy link
Contributor

Sorry, let me check why we couldn't merge that.

@stale
Copy link

stale bot commented Jan 15, 2020

This issue has been automatically marked as stale because it has not had recent activity. Thank you for your contributions.

@stale stale bot added the stale label Jan 15, 2020
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

Successfully merging a pull request may close this issue.

5 participants