Open dorovl opened 4 years ago
I think if you are using sbus then you want E4 connector (pin 4).
@mirkix can confirm this but look at the bottom of this post of his.
@Andrewiski Yes, you are right, SBUS is an inverted signal, that is the reason it can not be received by /dev/ttyO4
, use E4 pin 4 for SBUS.
@dorovl
What I omitted to say is that before going into the DSM2 connector, I'm using a MOSFET transistor to invert the signal from SBUS to IBUS . This works perfectly, provided the code from HAL_Linux_Class.cpp is modified as reported previously.
This setup allows the QEP_4B pin (or P8_15) to be used by the PRU's ECAP for another very valuable purpose like checking the PWM output signal integrity (the pin mux is in Mode 5, i.e. pr1_ecap0_ecap_capin_apwm_o).
By using this method, I detected some erratic PWM signal failures, caused by a wrong initialization of the PRU's IEP timer counter (takes sometimes 5 steps instead of 1 step). This was confirmed with the oscilloscope. I just found a fix yesterday (not yet submitted). I will provide more detailed explanation today.
Only way I would think we could handle this would be to pass in a config argument.
I would think this approach would also help fix the dsm 10 bit 11 bit detect as well as it could be passed in with a -R /dev/ttO4/sbus or -R /dev/ttO4/dmsx11
From what I can tell in the Copter-4.0 DSM code we get out of sync we wait 5 packets then restart the detect method when it would only change if we changed it on the transmitter or did a rebind.
I think that it would be a good approach!
In my opinion, because UARTs are hardware specialized devices, it is preferable to implement serial communications through a dedicated physical circuit, rather than with software running on PRU. Fortunately the UART of the AM335x supports nonstandard baud rates, allowing to cope with IBUS speed of 100'000 bps.
Besides the possibility to use the PRU's ECAP input pin for PWM signal integrity checks, it might be possible to measure, for example, the helicopter rotor speed (sensed via the governor's hall sensor).
Below are some notes about how I configured the system. Maybe it helps:
To convert from PWM signals to SBUS I used an inexpensive Signal Converter Module SBUS-PPM-PWM (S2PW) from https://hobbyking.com/en_us/signal-converter-module-sbus-ppm-pwm-s2pw.html.
I realized the inverter with a cheap 2N7000 Field Effect Transistor, a 1MΩ resistor in the Gate and a 560 Ω resistor between the 3.3V and the Drain:
Note: this leads to a pretty good switching performance (the 2N7000 transistor is recommended for low-power switching applications):
Signal frame: SBUS on channel 1 (yellow) and IBUS (inverted SBUS) on channel 2 (cyan)
Leading edge: SBUS on channel 1 (yellow) and IBUS (inverted SBUS) on channel 2 (cyan)
Trailing edge: SBUS on channel 1 (yellow) and IBUS (inverted SBUS) on channel 2 (cyan)
After that, one might apply the fix on HAL_Linux_Class.cpp described above, compile and test with:
debian@beaglebone:~/ardupilot/build/blue/examples$ sudo ./RCInput
I plan to fix the issue with the initialization of the PRU's IEP timer counter step next days making some documentation (demonstration test, fix proposal, etc.).
Bug report
Issue details
I use the DSM2 connector (/dev/ttyO4) on the BeagleBone Blue with SBUS (I use a PWM to SBUS converter).
To make-it working, I replaced in HAL_Linux_Class.cpp at line 140:
static RCInput_Multi rcinDriver{2, new RCInput_AioPRU, new RCInput_RCProtocol(NULL, "/dev/ttyO4")};
by:
static RCInput_Multi rcinDriver{2, new RCInput_AioPRU, new RCInput_RCProtocol("/dev/ttyO4", NULL)};
The fist argument initializes the SBUS, while the second the DSM2 protocol:
According to my tests, both arguments are mutually exclusive, i.e. doesn't work with both protocols like below:
static RCInput_Multi rcinDriver{2, new RCInput_AioPRU, new RCInput_RCProtocol("/dev/ttyO4", "/dev/ttyO4")};
Version master
Platform [ ] All [ ] AntennaTracker [x] Copter [ ] Plane [ ] Rover [ ] Submarine
Airframe type Single rotor helicopter
Hardware type BeagleBone Blue