OBAL - A Simple Linux-based Raspberry-Pi Ardupilot FCB

Ppm is already working, but I don’t get ibus working on it. It tested ibus with some modified version of a ibus test program for MCU’s on my raspberry but it looks like, ardupilot don’t recognize it. Did I something wrong? On start I give it the right serial with F parameter and in parameters I set serial5 protocol to rcin

Ok, looked I little bit into the code, looks like ibus isn’t integrated for Linux systems…

The function _process_rc_pulse in RCInput is called from RCInput_RPI.
The same PPM technique should work on SBUS.
I have not tried it but I am talking code wise.

I don’t get it working. But isn’t 100000 baud I little to fast for a normal gpio pin?
Btw, I have a python script that has no problem to decode ibus on the same hardware

Edit:
I got it working by using the RCInput_RCProtocol driver instead of the RCInput_RPI driver

Would you share this configuration please so that I can add it as an option to OBAL gitub
Thanks

In libraries/AP_HAL_Linux/HAL_Linux_Class.cpp around line 143 is the RC input driver.
I used following line to be able to use both:

static RCInput_Multi rcinDriver{2, new RCInput_RCProtocol(nullptr, nullptr), new RCInput_RPI()};

Both ppm and ibus are working with this, but when connected both at the same time, ardupilot gets a little confused. It should be able to make sbus too, when the uart hardware is right

Initialize RCInput_RCProtocol with null (nullptr, nullptr) this should open no drive as per file RCInput_RCProtocol.cpp line 44
int RCInput_RCProtocol::open_sbus(const char *path)

Yes, but if you define a serial port with protocol RCIN it automatically detects it

So you
1- Define static RCInput_Multi rcinDriver{2, new RCInput_RCProtocol(nullptr, nullptr), new RCInput_RPI()};
2- connect the SBUS from RX receiver to serial port RX ?
3- define Serial Port Protocol RCIN

and then the board can detect SBUS

Is this what do ?

I did it with ibus instead of sbus, but yes, it worked for me this way

1 Like

Yesterday I tried to connect this RX. I used SBUS pin to GPIO5 and RCInput_RPI could not detect the input.
Then I tried RCInput_Multi rcinDriver{2, new RCInput_RCProtocol("/dev/serial0", nullptr), new RCInput_UDP()}; and connected SBUS to RX again I received nothing.

I am not sure why ?

I think sbus need to be inverted, that’s why I use ibus

1 Like