I started this project as an attempt to reduce the amount and cost of hardware required to control a UAV. Since many UAVs already have a radio modem as their telemetry link, I wanted to try piggybacking a control link over the radio modem instead of using a typical RC TX/RX combo.
My goals were to have a fully-featured remote control unit that is low cost and highly configurable. I wanted my system to be compatible with any flight controller that accepts a PPM sum as its input. This includes the MultiWii and Paparazzi controllers.
Since I don't have a lot of time on my hands at the moment, I am releasing my code in hopes that someone will be able to use my work in their own project.
Feature List
20 Hz update rate
<50ms latency
High quality PPM using hardware timer and output pin
Low bandwidth (22char/sec min, 440char/sec max for 8 servos + 12 buttons)
Efficient update system – changes to the joystick are sent up to 19 times per second, full update is sent once per second
Text file configuration of many features including: PPM characteristics, servo count, button count, I/O pins, navigation lights, voltage readings
Commlink passthrough for external devices via second UART (ATmega w/ two UARTs required)
Joypad rumble on signal degradation/loss
Hardware
For my setup I used a Playstation 2 controller w/ USB adapter, Xbee radio modems, and an ATMega328P based board. You can probably modify the project to use a different radio modem or a different joystick input without too much trouble.
Here is a diagram of my test circuit:
I've also uploaded the original Eagle files to the code.google.com repository that houses the project.
My basic setup is: a PS2 controller w/ USB adapter (from eBay), this is connected to the Ground Control Station which is running Linux. I use a USB to TTL adapter w/ 3.3V output to connect to and power the GCS Xbee.
On the UAV I have the circuit from the diagram above. The PPM output is connected to the PPM SUM input for MultiWii, or any other compatible flight controller.
PPM via the ATMega Hardware Timer and Output Pin
The PPM signal is generated using the Hardware Timer and Output Pin. Many PPM examples that I came across did not use the Fast PWM feature, instead setting the output pin to high or low inside the ISR, and I think there is room for improvement on this. Using Fast PWM allows you to shorten your ISR function and reduce the number of instructions per interrupt.
I used an array to store the PPM pulse lengths. The array is (Servo Count * 2) + 1 in length and stores the length of each servo pulse and all sync pulses. For example, if we have 8 servos that are all in neutral position, a minimum pulse of 1ms, a maximum pulse of 2ms, a high pulse of 200usec, and a sync pulse of 3ms our array would contain:
1500, 200, 1500, 200, 1500, 200, 1500, 200, 1500, 200, 1500, 200, 1500, 200, 1500, 200, 3000
Our ISR is as follows:
ISR(TIMER1_COMPA_vect) {
OCR1A = ppmInfo.pulses[ppmInfo.currentPulse]; // Set OCR1A compare register to our next pulse
ppmInfo.currentPulse++; // Increment the pulse counter
if(ppmInfo.currentPulse >= configInfo.ppmPulses) { // If the pulse counter is too high reset it
ppmInfo.currentPulse = 0;
}
}
As you can see it simply sets the Compare Match counter to the next pulse length, then it increments the current pulse count until it becomes out of bounds, in which case it is reset to 0.
Fast PWM handles the pin state changes every time the interrupt occurs. One issue that I ran into was that because Fast PWM mode toggles the output pin state on every interrupt, and there is no way to set the initial state, it is possible for the PPM signal to become inverted. In order to avoid this I had to set the timer into CTC Mode w/ Output Pin High on match, then force a match using the TCCR1C register, then put the timer into Fast PWM mode and start the PPM signal up. This forces the pin into the correct state for the start of our PPM signal.
Setup/Configuration
encoder.rc – This file configures the PPM encoder board. It allows you to configure the PPM characteristics, output pins, voltage readings, and button to pin mappings.
Configuration fields:
Debug Pin, Status LED Pin, Navlight Pin – Output pins for Debug, Status, and Navlight lights.
RSSI Pin – Input pin for reading RSSI
Main Battery Pin, Comm Battery Pin, Video Battery Pin – ADC input pins for various batteries
Lost Message Threshold – Time (ms) without a command from the ground station before the PPM encoder assumes it has lost its signal
Heartbeat Interval – Frequency (ms) to send heartbeat to the ground station
Ping Interval – Frequency (ms) to send a ping request to the ground station
PPM Min Pulse, PPM Max Pulse, PPM High Pulse, PPM Sync Pulse – PPM characteristics
Status Interval Signal Lost – Toggle interval for status LED if signal is lost
Status Interval OK – Toggle interval for status LED if signal is OK
Navlight Interval – How frequently to toggle navigation lights
Servo Count, Button Count – Servo and Button counts
Button Pin Map – Map for buttons to output pins (pushing a button drives the pin high)
ADC Sample Rate – Sample rate for the ADC
Voltage Samples – Number of battery voltage samples to average before transmitting to ground station
js_ctrl.rc – This file configures the radio modem port, joystick, and event device files. It also allows you to configure a throttle safety, button state count, and heartbeat interval.
XBee Port File, Joystick Port File, Joystick Event File – Devices files for the Xbee, joystick, and rumble event.
Joystick Discard Threshold – Inputs to the joystick below this threshold will be ignored. For example, the joystick I used (PS2) reads values from -32767 to 32767, with 0 being neutral. 32767 is quite a lot of steps for how little distance the joysticks physically move, meaning it is very easy to create a lot of input in the lower ranges unintentionally just by resting your thumbs on the joysticks. We don't want to transmit these types of unintentional movements.
PPM Interval – Frequency (ms) of an entire PPM frame (used to determine when to send full control updates)
Timeout Threshold – Time (ms) without a heartbeat from the airframe before the signal is considered lost
Button State Count – Count of how many states each button has, 0 means the button updates on press/release. 1 means the button is a toggle – press once to turn it on, press again to release.
Context Button – Allows a button to toggle a separate joystick context, wherein the joystick axis to servo mapping changes. This allows you to, for example, hit a button and have your pitch/roll remap to a camera pan/tilt.
Heartbeat Interval – Frequency (ms) to send a heartbeat
Ping Interval – Frequency (ms) to send a ping request
Servo Count, Button Count – # of servos and buttons
Throttle Safety – Time (in seconds) for throttle safety to remain on after program starts
To Do
RSSI reading method needs overhaul
Configuration of individual PPM channels min/max length (trim)
Fix servo count configuration
Allow editing of configuration via menus
Allow mapping of joystick axes to servos via menus
Better user interface
Ground control module
Comments
Hi
Maybe this is useful for you folks :-)
http://headsoft.com.au/index.php?category=vjoy
You can even control and land your aircraft using GCS keyboard!
Thanks for posting that Paul. I've been starting to research driving a module from an RC Transmitter from a joystick. mostly because I think that I would be able to fly through tricky area's a lot easier with a nice joystick... I am beginning to think however that I might need to use an ARM processor to do it properly...
Thank you, Rana and Noth666!
I have done testing for 30m-1hr periods with a grounded UAV and it was able to preserve the link. If the signal is lost both the GCS and the UAV will begin to send out ping requests to each other at short intervals. If either program receives a ping request it will attempt to re-establish communication.
In my range testing I was able to go fairly far in open space but lost signal after only a hundred meters or so inside a dense city. Once the signal was lost I was able to get it back by walking back a couple meters.
One thing I would like to try is to switch out for different radios. Currently I am using an Xbee Pro-900 but I have an RFM22B and a cheap 2.4GHz SPI radio that I would like to try.
Jesse, I will add a diagram for a test circuit. Thank you for asking!
Thank you, Alberto!
I found a post somewhere on DIYDrones stating that their testing had shown that the Xbees work best at 57600 baud, did you try different baud rates in your project?
Still, I haven't had a chance to fly very far with mine. I'm still in the configuring/troubleshooting phase of the airframe building. I didn't start this project with a functional UAV in my possession. In retrospect that would have made things a lot easier. :)
My setup does have some provisions for losing the signal, though right now it just turns the PPM off.
Have you tried your system any longer time period?
Nice work ! Besides Paparazzi & Multi-Wii, Arduplane, Arducopter, UAVxArm32, Quanton etc all option to use PPM signal.
Have you got any details of the hardware?
Sounds great Paul! I did a custom tx/rx myself, but I kept it in the simple/lazy side. It worked on the bench, but some xbee blackout issues (and crashes!) made me giving up.
Your work looks impresive