mstrens / oXs_on_RP2040

version of openXsensor to be used on raspberry pi pico RP2040 (more protocols, more functionalities)
83 stars 22 forks source link

oXs failsafe and flags #127

Closed hw999 closed 4 months ago

hw999 commented 4 months ago

I observed on a Frsky RB10 (redundancy box) an inconsistent response of the RB when setting the oXs into failsafe. The RB did not switch to the still operating input channel but stayed on the datastream of the oXs in failssafe.

I monitored the SBUS-datastream of the oXs with https://github.com/bolderflight/sbus and found out that in failsafe neither the frame-lost nor the failsafe flags were set. I tested a couple of times with consistent results.

Its obvious that the RB can't work without these flags properly set. I caution everybody about using an RB together with an oXs for the time being.

mstrens commented 4 months ago

You are right. Currently the 2 flags are not managed. I could add some code to manage them.

Just for my understanding:

mstrens commented 4 months ago

I put version 2.12.1 on github (in test branch). This version is supposed to transmit the missing and the failsafe flags received in sbus frames (on PRI and or SEC).

This is not yet done for protocols where oXs does not read a sbus signal (so also not yet for when oXs expect an sbus2, ELRS, ...). I expect it should work for FRSKY protocol but I did not test it.

hw999 commented 4 months ago

Hi mstrens thanks for reply. I use ELRS with two RXs, one is feeding the oXs and the SBUS goes from there to the RB10. The second RX goes directly to the RB10.

sbus_out_pwm.cpp line 162 : I see that you set sbusFrame.flag = 0x10; // indicates a failsafe. Why does it not show up later on ?

hw999 commented 4 months ago

To make it more clear : Rx-1 --- CRSF ---- oXs ----- SBUS ---- RB10 Rx-2 --- SBUS --- RB10 The RB10 is a redundancy box, not a receiver. I don't use Frsky Rf protocol.

mstrens commented 4 months ago

Thanks for pointing this out. First : setting the value to 0X10 is a bug. The failsafe flag is bit 3 and missing flag is bit 2. In version 2.12.2, I changed this and set the value to 0X0C.

Second: the line that set the flag on 0X0C (ex 0X10) is used only when oXs does not get anymore a signal from the receiver. When a receiver provides a Sbus signal, this will happen normally only if the wire between the receiver and oXs is disconnected. If a receiver providing a sbus (like a Frsky) loose the rf signal, it will continue to generate a sbus signal (with the failsafe flag set). In this case, oXs will just get this sbus and does not use the line with 0X0C. I made now a change that let oXs forward the flags set in an incoming sbus signal. So if Rf signal is lost, sbus out should communicate it to RB.

As far I know, ELRS transmit RC frames (in CRSF format) to flight controller (or oXs) only when RF link is OK. When rf connection is lost, ELRS stop providing frames. This will be considered by oXs like a disconnected wire and so oXs wil use the line of code you identified. Now that I change the value from 0X01 to 0XC0, the right bits should be set and your RB should detect it.

mstrens commented 4 months ago

To make it more clear : Rx-1 --- CRSF ---- oXs ----- SBUS ---- RB10 Rx-2 --- SBUS --- RB10 The RB10 is a redundancy box, not a receiver. I don't use Frsky Rf protocol.

Yes. I now understood it. I expect that you know that you can also use oXs for redundancy. This year, I will use 2 ELRS receivers (one with telemetry OFF) connected to one oXs. Then oXs will provide PWM and Sbus based on signal from any ELRS receiver. It is less secure than using a RB but it is cheaper and take less space in small models.

hw999 commented 4 months ago
    if ( ( millisRp()- lastRcChannels) > FAILSAFE_DELAY ) { // if we do not get a RC channels frame, we apply failsafe
        sbusFrame.flag = 0x0C; // indicates a failsafe and missing 
        if (config.failsafeType == 'C') memcpy( &sbusFrame.rcChannelsData , &config.failsafeChannels, sizeof(config.failsafeChannels));
    } else {
        sbusFrame.flag = 0x00;
        if (sbusOutMissingFlag) sbusFrame.flag |= 0X01 << 2;   // set the flags
        if (sbusOutFailsafeFlag) sbusFrame.flag |= 0X01 << 3;
    }    

Are these the only changes to the code related to the SBUS stuff ? sbusOutMissingFlag and sbusOutFailsafeFlag : were they added today ?

I let you know whether it works or not.

mstrens commented 4 months ago

sbusOutMissingFlag and sbusOutFailsafeFlag have been added today. They are currently filled only in sbus_in.cpp

I should check if there are other files (protocols) where it should be coded too.

hw999 commented 4 months ago

Thanks a lot. Made a quick test .Looks promising for the time being.