TxDuino: Custom PC Controlled RC Transmitter



In our lab we have some very light weight foam aircraft that we do control work with. In order to keep the weight down, we use micro RC receivers that generate PWM signals for each of the servos that deflect one of three control surfaces: ailerons, elevator, and rudder. Note that both ailerons are linked and are together controlled by a single servo (a common setup for these lightweight foam planes). A PWM signal is also sent to control the throttle of the propeller. The glowing little spheres are reflective features to aid in motion capture which we use for estimation of the vehicle's state.

[caption id="attachment_255" align="aligncenter" width="300" caption="One of our 'lil baby airplanes"]![One of our 'lil baby airplanes](http://128.31.5.103/wordpress/wp- content/uploads/2009/10/PA300001-300x225.jpg)[/caption]

The trick, however, is to get our control codes, running on a PC somewhere in the room, to actually change the deflection of the airplane's control surfaces, or the throttle of the propeller.

The TxDuino project aims to create a single device that allows a PC to control an RC vehicle. At the time of starting this project, the only option for doing this was a device from here that could be plugged into the trainer port of a transmitter. An arduino has been used to achieve this same setup as described here. Going through the handheld transmitter, however, is a huge hassle for a number of reasons so I set out to create a simple single device that could accomplish this. As it turns out, so did the guys at Tom's RC, their solution being this guy here. Anyway, since the work is done, I'll share the results.

The easiest way that I figured to pull this off is to work with a modular RC transmitter, and interface directly with the module. For instance this is a transmitter

[caption id="attachment_237" align="aligncenter" width="300" caption="Futaba Modular Transmitter"]![Futaba Modular Transmitter](http://128.31.5.103/wordpress/wp- content/uploads/2009/10/PA190140-300x225.jpg)[/caption]

And this is the module that plugs into the back of the transmitter

[caption id="attachment_238" align="aligncenter" width="167" caption="the FP- TP-FM Transmitter Module"]![the FP-TP-FM Transmitter Module](http://128.31.5.103/wordpress/wp- content/uploads/2009/10/PA300002.jpg)[/caption]

The handheld part creates some kind of signal that it sends to the module, which does something, and then sends something else to the antenna. If I can figure out how to recreate that signal, then the "somethings" aren't very important. The modules are cheap enough and easy enough to find that there isn't much of a need to re-engineer that part.

To begin with, I needed to do some investigation. There are 5 pins on the back of the transmitter. It was easy enough by tracing the module circuit to find the source, ground, and RF out (antenna) pins, but what about the other two? I was hoping one of them was the control signal in a not too esoteric form, and I had no idea what the last would be. I managed to find the control signal with a little probing. Here is a little video showing the transmitter (Tx) hooked up to the module, via some wires with alligator clips which made it easy to investigate things.

After figuring our a little of what was going on, I found this forum post that had a pretty good discussion of the pinouts on this particular module. In particular, this post I found to be accurate and helpful.

Basically, looking at the back of the transmitter (or the top of the module, when the cover is off) the pins are

        1   2   3   4   5
        .   .   .   .   .

     left side
     #1 PPM
     #2 V+
     #3 RF check
     #4 ground
     #5 RF out
     right side

Of particular importance is the note on that post that the hand-held part is actually pulling the line low to make the pulses, and that the PPM line is at 2.5 volts.

I found a description of the PPM signal here. While the measurements I made using the oscilloscope did not match the information on that page exactly (I measured a 4us pulse between channels), using the signal description from that page has had good results. The details of the PPM frame are repeated here.

  • complete PPM-Frame has a length of 22.5 ms.
  • consists of an overlong start segment combined with 8 analog channels.
  • stop pulse of 0.3 ms follows every channel's impulse.
  • The length of a channel's impulse ranges from 0.7ms to 1.7 ms

Below is a video of the PPM signal from the transmitter. You can see the impulse length for each channel changes as I manipulate the control sticks on the handheld part of the transmitter. I apologize for the poor light sensing on my crappy little digital camera. Also, note that channel 5 jumps up and down because it is a flip switch (see the photo above) and only has two possible positions.

Ok, now that I know what is happening, I need a way to recreate that PPM signal using some kind of device that I can connect to my PC. Hey, the arduino is easy to develop with, comes with a USB controller, and has a nice software library that handles the PC interface stack. It's also built around an Atmel microcontroller (my decimila specifically uses a ATmega168L) which has some pretty sophisticated features. It runs at 16Mhz, has three timers that can be used for generating interrupts, and comes with a (relatively) standard C / C++ compiler for writing code. Furthermore, the arduino's bootloader means that I don't even have to worry about messing with a programmer to get something up and running.

I wont go into all the gory details of the TxDuino design, but I will point out some of the relevant considerations.

The 168L has three timers. Timer1 is a 16-bit counter, Timer0 and Timer2 are 8-bit counters. Timers 0 and 1 share a prescaler, Timer2 has it's own. The prescaler is a component that reduces the update rate of the timer, so we can scale the 16Mhz system clock to some fraction of it's rate. Using an 8-bit counter would be extremely limiting because scaling the clock down enough that the counter capacity is sufficient would provide a counter resolution that is too coarse for the fine control we need to generate our waveform. This means I want to use Timer1. However, Timer0 is used by the serial stack. I want to be able to send commands from the PC to the TxDuino which will require use of the serial interface. Thus, the serial baud rate will dictate the prescale factor used by Timer0, and thus used by Timer1… meaning that my choices are limited to whatever the serial stack allows.

A simple arduino test program, however, quells this dilemma.

 int inByte = 0;         // incoming serial byte

 //define the Timer1 overflow interrupt service routine
 ISR(TIMER1_OVF_vect) 
 {
    // print out the current value of the timer control register B which
    // contains the timer prescale value, set when the serial BAUD rate 
    // is defined
    Serial.print("Timer1: ");
    Serial.print(TCCR1B, HEX);
    Serial.print("rn");
 }


 void setup()
 {
   // set Timer1 to operate in "normal" mode
   TCCR1A = 0;

   // activate Timer1 overflow interrupt 
   TIMSK1 = 1 << TOIE1;

   // start serial port at 9600 bps:
   Serial.begin(9600);
 }

 void loop()
 {
   // if we get a valid byte, read analog ins:
   if (Serial.available() > 0) {
     // get incoming byte:
     inByte = Serial.read();
     Serial.print(inByte, BYTE);
     Serial.print("rn");
   }
 }

This program sets the serial baud rate to 9600 bits/sec, and then prints out the value of the Timer1 control register. A subset of the bits in that register indicate what the prescaler is set to, and thus what the prescale factor is. Running this program, and looking at the datasheet, I was able to determine that the prescale factor is set to 64. This means that the timer resolution for Timer1 is

[latex size="2"] \frac{ 64 \frac{ \text{system ticks}}{ \text{counter tick}} } {16,000,000 \frac{ \text{system ticks}}{ \text{second}}} = 0.000004 s = 4 \mu s[/latex]

And the 16-bit timer has a range of zero to

[latex size="2"] (2^{16} - 1) \cdot (4 \mu s) = 65535 \cdot 4 \mu s = 262140 \mu s = 262+ ms [/latex]

Since our frame length is 22.5 ms, we have plenty of range to work with. Also, the range on the individual servo channels is 1000 us, so that gives us 1000/4 = 250 possible steps for each channel (251 possible discrete positions). That gives us a resolution of better than +/- 0.5% for each channel, which is quite acceptable.

Also, since the PPM signal pulls the voltage on the line low, we cannot just use digitalWrite() like we usually do when writing to a pin with the arduino. Instead, we need a way to drive the voltage to zero when we want to pull the line low, and a way to basically "do nothing" when we want the line high. We can do this by setting the pin voltage to LOW, and then switching between INPUT and OUTPUT using pinMode()

The last consideration is the serial packet format. I decided to keep things simple. Since each channel can only have 251 possible values, I used an unsigned 8-bit integer ([latex]2^8 - 1 = 255[/latex] possible values for an 8-bit number) for each channel, with values 0-250, and reserving 0xFF (255 in decimal) as a end-of-packet identifier.

Here is a little test code to demonstrate the use of pinMode() to set the voltage of the line high / lo. It listens for either an 'a' or 'b' character over serial, and sets the line high or low depending on what is sent. If you want to play with this, you can use the terminal from within the Arduino software to send the commands.

int inByte      = 0;    // incoming serial byte
int ppmPin      = 2;    // pin to make the waveform on


// to setup the device, we will initialize all the channels, and initialize the
// timer settings
void setup()
{
    // start serial port at 9600 bps, note that this also sets the Timer1
    // prescaler, so we need to ensure that we don't change it later; a test 
    // using a previous program showed that 9600 baud set the prescaler to 64
    // or the Timer1 control register B to 0x03.
    Serial.begin(9600);

    // we configure the signal pin as an input; not that the signal actually is
    // an input but we modify the signal by pulling it low when we need to
    pinMode(ppmPin, INPUT);


    // then we set the inital state of the pin to be low
    digitalWrite(ppmPin, LOW);
}


// the main routine monitors the serial port, and on receipt of a completed 
// packet will recalculate the compare points for the specified signal
void loop()
{
    // if there's a byte available on the serial port, then read it in
    if (Serial.available() > 0)
    {
        // get incoming byte
        inByte = Serial.read();

        switch(inByte)
        {
            case 'a':
                pinMode(ppmPin, OUTPUT);
                Serial.print("setting pin lown");
                break;

            case 'b':
                pinMode(ppmPin, INPUT);
                Serial.print("setting pin highn");
                break;

            default:
                break;
        }
    }
}

Here is a photo of the arduino hooked up with a resistor from the PPM pin to ground which allows me to look at the signal as I'm testing. The wire from the right side of the resistor to the ground terminal on the arduino is hidden behind the black probe. The other things connected to the breadboard are the transmitter module (the thing in the metal shield), and the back circuit board from the transmitter (the green thing; the pins from that board are plugged into the breadboard). The red thing is the battery for the transmitter.

[caption id="attachment_277" align="aligncenter" width="300" caption="Arduino Test Setup"]![Arduino Test Setup](http://128.31.5.103/wordpress/wp- content/uploads/2009/10/PA260169-300x225.jpg)[/caption]

Well that's pretty much it as far as background and design. Here is the final code that I used to generate the desired waveform. I wont describe it much here since it's heavily commented already. Basically it uses two compare match interrupts with Timer1. The two interrupts leap-frog each other and signal either a rising edge or a falling edge. The counter is not cleared when the interrupts are serviced, until the last falling edge is serviced.

int inByte      = 0;    // incoming serial byte
int ppmPin      = 2;    // pin to make the waveform on
int chan[8];            // 8 channels encoded as 250 * (percent range)

int compA[9];           // 9 compare points for Timer1
int compB[9];           // 9 compare points for Timer2
int iCompA      = 0;    // compare point index for currently active
int iCompB      = 0;    // compare point index for currently active


// the 0xFF byte will serve as a packet delimeter, we don't want to read
// garbage from the serial so we'll start as soon as we get one of those but
// not before
int bDelimReceived  = 0;

// we don't want to write to any of the compare registers unless we have to 
// so we'll only do so at the end of a frame if that frame involved a change
// in the current signal
int bSignalChanged  = 0;

// index for which channel is next to read in
int iChan = 0;


// define the Timer1 compare match interrupt service routine for the rising 
// edge
ISR(TIMER1_COMPA_vect) 
{
    // to set the line high, we switch the pin mode to "INPUT"
    pinMode(ppmPin, INPUT);


    // if this is not the last rising edge
    if( iCompA < 8 )
    {
        // then we change the compare register to issue an interrupt at the next
        // rising edge, by incrementing the compare point counter
        iCompA++;

        // and then setting the compare register
        OCR1A = compA[iCompA];
    }

    // if this is the last rising edge then we need to set the compare
    // register to be at the time of the rising edge following the start 
    // frame
    else
    {
        // first, if the signal has changed since while writing the last frame
        // then we need to update the compare points
        if( bSignalChanged )
        {
            compA[0] = 3550;
            for(int i = 0; i < 8; i++)
                compA[0] -= chan[i];

            // the end of the first pulse is 75 ticks (300us) after that
            compB[0] = compA[0] + 75;

            // and then the rest of the compare points depend on the value of
            // each channel
            for(int i = 1; i < 9; i++ )
            {
                compA[i] = compB[i-1] + chan[i-1] + 175;
                compB[i] = compA[i] + 75;
            }

            bSignalChanged = 0;
        }

        // then we set the compare point to match the end of the start segment
        iCompA  = 0;
        OCR1A   = compA[0];
    }

}

// define the Timer1 compare match interrupt service routine for the falling 
// edge
ISR(TIMER1_COMPB_vect) 
{
    // to set the pin low we open the collector
    pinMode(ppmPin, OUTPUT);


    // if this is not the last falling edge
    if( iCompB < 8 )
    {
        // then we change the compare register to issue an interrupt at the next
        // rising edge, by incrementing the compare point counter
        iCompB++;

        // and then setting the compare register
        OCR1B = compB[iCompB];
    }

    // if this is the last falling edge
    else
    {
        // then we wrap around to the beginning
        iCompB=0;

        // and set the compare register
        OCR1B = compB[iCompB];

        // and we also need to reset the timer because this is the end of the 
        // frame
        TCNT1 = 0x00;
    }

}






// to setup the device, we will initialize all the channels, and initialize the
// timer settings
void setup()
{
    // initialize all eight channels to be at 125, or neutral
    for(int i=0; i < 8; i++)
        chan[i] = 125;

    // initialize the throttle to be "full left" which is actually "full stop"
    chan[2] = 0;

    // start serial port at 9600 bps, note that this also sets the Timer1
    // prescaler, so we need to ensure that we don't change it later; a test 
    // using a previous program showed that 9600 baud set the prescaler to 64
    // or the Timer1 control register B to 0x03.
    Serial.begin(9600);

    // set Timer1 to operate in "normal" Mode, and set the
    // prescaler to 64; the default mode is one of the PWM modes so we need to
    // set this
    TCCR1A = 0;

    // note: Timer0 and Timer1 share a prescaler, and Timer0 is used by the 
    // serial lines. Therefore, we cannot pick the value of the prescaler, 
    // rather it is determined by the baud rate we want. A simple program has 
    // shown that setting the baud rate to 9600 involves setting the prescaler 
    // to 64

    Serial.print("Timer Control Registers: n");
    Serial.print("   A: 0x");
    Serial.print(TCCR1A, HEX);
    Serial.print("n");
    Serial.print("   B: 0x");
    Serial.print(TCCR1B, HEX);
    Serial.print("n");

    // set the Timer1 output compare register A to 3550 ticks, which corresponds 
    // to 14,200us with the prescale set to 64; the math goes like this: 
    //    with the prescaler set to 64, the Timer1 period is 64/16e6 = 4us
    //    want an interrupt issued after 22.5ms - 8*700us - 9*300us = 14,200us
    //    means we want an interrupt issued after 14,200/4 = 3550 ticks
    compA[0] = 3550;
    OCR1A = compA[0];

    // set Timer1 output compare register B to something 300us/4us = 75 ticks 
    // after the first compare point for timer A
    compB[0] = compA[0] + 75;
    OCR1B = compB[0];

    // we can go ahead and initialize all the other compare points as well, we
    // know that all the channels are set to zero, but I'll do this the long 
    // way because it'll match code that we use elsewhere in this program
    for(int i=1; i < 9; i++)
    {
        compA[i] = compB[i-1] + chan[i-1] + 175;
        compB[i] = compA[i] + 75;
    }

    // activate Timer1 output compare interrupt with compare register A and
    // compare register B by setting the Output Compare Interrupt Enable bits
    TIMSK1 = 1 << OCIE1A | 1 << OCIE1B;


    // we configure the signal pin as an input; not that the signal actually is
    // an input but we modify the signal by an open collector so to make the
    // signal high we enable a 20K pull-up resistor, and to make the signal 
    // low we open the collector
    pinMode(ppmPin, INPUT);


    // then we set the inital state of the pin to be low
    digitalWrite(ppmPin, LOW);
}



// the main routine monitors the serial port, and on receipt of a completed 
// packet will recalculate the compare points for the specified signal
void loop()
{
    // if there's a byte available on the serial port, then read it in
    while (Serial.available() > 0)
    {
        // get incoming byte
        inByte = Serial.read();

        // if the byte is a packet delimiter, then start recording the new 
        // packet by resetting the channel indexer
        if( inByte == 0xFF )
        {
            bDelimReceived  = 1;
            iChan           = 0;
        }

        // otherwise, if we've recieved at least one packet delimiter and the
        // current channel index is valid, then record the chanel value; 
        else if(bDelimReceived && iChan < 8)
        {
            // we can save some processing time by only updating the stored 
            // values if the incoming command has changed, so we'll condition
            // the calculations on the fact that the byte is different than
            // what is already stored
            if(inByte != chan[iChan])
            {
                // the protocol is defined to send values between 0 and 250 
                // inclusive, for 250 distinct values; the timing increment is 
                // between 0 and 250 so we simply store the value
                chan[iChan] = inByte;

                // since the signal changed, we need to raise the flag
                bSignalChanged = true;
            }

            // then we increment the channel index so that we're ready for 
            // the next byte that's sent
            iChan++;
        }
    }
}

In order to test this, I wrote this little program to send a sinusoidal input to the TxDuino. Note this code is specific to windows.

/**
 *  file       serialTest.cpp
 *  date:      Oct 27, 2009
 *  brief:
 *
 *  detail:
 *  This is a simple test program that demonstrates how to connect to and
 *  write commands to the arduino transmitter interface using windows.
 *
 *  the TxDuino is an interface into the futaba FP-TP-FM transmitter module,
 *  which accepts an RC PPM input. This signal contains a maximum of 8
 *  servo channels.
 */

#include 
#include 
#include 
#include

#define PI 3.14159265

int main( int argc, char** argv )
{
    using std::cout;
    using std::endl;
    using std::sin;
    using std::setw;

    // check to ensure that the command line included a device to open
    if( argc < 2 )
    {
        cout << "Usage: serialTest.exe [Device Name]n"
                "   where [Device Name] is the name of the COM port file onn "
                "   windows (i.e. \\.\COM8), or the name of the serialn "
                "   device on *nix (i.e. /dev/tty8)n" << endl;

        return -1;
    }

    // grab a pointer to the device to open
    char*       strDevName = argv[1];

    // open the file using the windows API
    HANDLE      hComPort         =
    CreateFile( strDevName,
        GENERIC_READ | GENERIC_WRITE,       // access mode: read and write
        FILE_SHARE_READ|FILE_SHARE_WRITE,   // (sharing)
        NULL,                               // (security) 0: none
        OPEN_EXISTING,                      // (creation) i.e. don't make it
        0,                                  // (overlapped operation)
        NULL);                              // no template file

    // check to make sure the file open succeeded
    if( hComPort == INVALID_HANDLE_VALUE )
    {
        cout << "FATAL, Invalid device name: " << strDevName << "n" << endl;
        return -2;
    }

    // get the current settings on the com port
    DCB dcb;
    GetCommState( hComPort, &dcb );

    // change the settings, the TxDuino uses a BAUD rate of 9600
    dcb.fBinary     =   1;
    dcb.BaudRate    =   CBR_9600;
    dcb.Parity      =   NOPARITY;
    dcb.ByteSize    =   8;
    dcb.StopBits    =   ONESTOPBIT;

    // set the new settings for the port
    SetCommState( hComPort, &dcb );

    // allocate the data buffer for sending over serial
    unsigned char data[9];

    // set the last byte to be the stop byte
    data[8] = 0xFF;

    // send a sinusoidal input on all channels (except for channel 3, which is
    // usually the throttle) for 10 seconds
    for(int i=0; i < 1000; i++)
    {
        for(int j=0; j < 8; j++)
            data[j] = (unsigned char)(125.0 + 75.0 * sin( 2.0 * PI * i / 100.0 ));

        data[2] = 0;
        data[8] = 0xFF;

        for(int j=0; j < 8; j++)
            cout << setw(3) << (int)data[j] << " | ";
        cout << endl;



        DWORD bytesWritten;

        BOOL retVal =
        WriteFile(  hComPort,       // output handle
                    data,           // buffer of bytes to send
                    9,              // number of bytes to send from buffer
                    &bytesWritten,  // pointer to a word that recieves number of
                                    // bytes written
                    NULL);          // pointer to an OVERLAPPED struct

        Sleep(1);
    }


    // close the device
    CloseHandle( hComPort );

    return 0;
}

The result of running this test program with the probes attached to the arduino is below.

Then I disconnected the line from the handheld part of the transmitter to the module, and connected the arduino's output instead. This is shown below.

[caption id="attachment_280" align="aligncenter" width="300" caption="Arduino Replacing PPM from Handheld"]![Arduino Replacing PPM from Handheld](http://128.31.5.103/wordpress/wp- content/uploads/2009/10/PA260170-300x225.jpg)[/caption]

By connecting the oscilloscope probes like this

[caption id="attachment_279" align="aligncenter" width="300" caption="Arduino Replacing PPM from Handheld with Probes"]![Arduino Replacing PPM from Handheld with Probes](http://128.31.5.103/wordpress/wp- content/uploads/2009/10/PA260171-300x225.jpg)[/caption]

I was able to test the output, which is shown here.

Everything looks good at this point. The next thing to do is connect the voltage and ground pins of the module directly to the batter, they RF out line to the antenna, and the RF good line to ground through a resistor. This is shown below. Note the module is underneath the little breadboard.

[caption id="attachment_282" align="aligncenter" width="300" caption="TxDuino Prototype"]![TxDuino Prototype](http://128.31.5.103/wordpress/wp- content/uploads/2009/10/PA290172-300x225.jpg)[/caption]

And when running the test program, this is what the airplane does.

And here you can see the waveform generated by the completed TxDuino prototype

[caption id="attachment_283" align="aligncenter" width="300" caption="TxDuino Prototype Moneyshot"]![TxDuino Prototype Moneyshot](http://128.31.5.103/wordpress/wp- content/uploads/2009/10/PA290173-300x225.jpg)[/caption]

And that's that.

Comments


Comments powered by Disqus