Sunday, May 20, 2012

RC Channels, L293D Motor Driver - Part 2 Calibration And Code

Creative Commons License
RCChannelsL293D by D Banks is licensed under a Creative Commons Attribution-NonCommercial-ShareAlike 3.0 Unported License.


The following post builds on previous posts relating to interfacing RC Equipment with micro controller projects.


The post covers Arduino calibration with RC Equipment and the transformation of RC Steering and throttle channels into the pin logic levels and left and right PWM signals required to provide full proportional control of a tracked vehicle using the common L293D motor driver.

Why Calibration ?
In the very fist post dealing with RC Equipment we discussed how an RC Channel Signal is made up of a train of around 50 pulses per second and that each pulse is between 1000 and 2000 microseconds in length with neutral being 1500 microseconds.

http://rcarduino.blogspot.com/2012/01/how-to-read-rc-receiver-with.html



In air applications the neutral point for the throttle channel is generally 1000 as braking and reverse are not available and so the full 1000 to 2000 microsecond range is used for forwards throttle control.

Many projects are based on the assumption that these values always apply, however this is not the case.

A variety of transmitter construction and environmental factors mean that we can rarely rely on neutral generating a pulse of exactly 1500 microseconds, nor should we expect full throttle, full braking or left and right end points to be exactly 1000 and 2000 microseconds. As an example, the values my transmitter provided by default are shown below -


Example minimum, center and maximum channel values from a Spectrum DX3S Transmitter/Receiver

Channel Value                      Actual Pulse Width             Percentage of Assumed Range
Full Left Steering108084.0
Full Right Steering190080.0
Center Steering14843.2
Full Brakes110878.4
Full Throttle191683.2
Neutral Throttle15244.8


Looking at the final percentage column we can see that the transmitter is sending only 80% of the expected range, this means our projects can only deliver 80% of their full performance.

A similar problem occurs with the throttle center point, the throttle channel is sending 1524 as the neutral point which corresponds to almost 5% throttle, this wastes power and causes unnecessary heat build up.

In order to overcome these problems I have built a simple 'one touch' calibration into the RCChannelsToL293 project.

One Touch Calibration

When the user presses the program button, the project enters PROGRAM_MODE for 10 seconds. During this time, the project examines all incoming signals to determine the highest and lowest value received.

All that is required is for the user to briefly apply full throttle and reverse then left and right steering for the code to record the end points.

The center points are captured immediately that program mode is entered, so it is important that the transmitter is in a neutral position when the program button is initially pressed.

Permanently Storing The Calibration

The project takes advantage of the ATMega microcontrollers onboard EEPROM memory to permanently store the end points. The user need only repeat the programing procedure if the transmitter/receiver is changed in the future.

The EEPROM (Electrically Erasable Programmable Read Only Memory) is a separate memory on the ATMega micro controller that can be used to store information between power cycles. To put it another way anything your store in EEPROM, is still going to be there when you reset the Arduino.

As we do not want to have to reprogram our RC Project every time we switch on, the EEPROM can be used to store settings and then read them in at power up.

The Code - Part 1 - Accessing the EEPROM

The Arduino provides a library for storing single byte values in EEPROM. To include the library in a project select Sketch/Import Library/EEPROM from the Arduino editor.

The library provides two functions EEPROM.read and EEPROM.write. These two functions work with a single byte at a time however the settings we want to store are held in two byte uint16_t variables. In order to read and write these variables we have to store and retrieve each byte separately.


// write a two byte channel setting to EEPROM
void writeChannelSetting(uint8_t nIndex,uint16_t unSetting)
{
  EEPROM.write(nIndex*sizeof(uint16_t),lowByte(unSetting));
  EEPROM.write((nIndex*sizeof(uint16_t))+1,highByte(unSetting));
}
 
// read a two byte channel setting from EEPROM
uint16_t readChannelSetting(uint8_t nIndex)
{
  uint16_t unSetting = (EEPROM.read((nIndex*sizeof(uint16_t))+1)<<8);
  unSetting += EEPROM.read(nIndex*sizeof(uint16_t));

  return unSetting;
}


Part 2 - Implementing The Program Mode

To capture the settings we want to store I have added a program button, when this button is pushed the following steps are performed -

1) Set the mode variable gMode to PROGRAM_MODE
2) Set ulProgramModeExitTime to ten seconds from now
3) Set the throttle and steering channel center points to the current pulse width - for this reason it is important that all transmitter channels are at the neutral position when the program button is pressed.
4) Set all other end points to RC_NEUTRAL
5) Set gDirection to DIRECTION_STOP - this is used at a later point in the code to disable the L293D


  if(false == digitalRead(PROGRAM_PIN))
  {
    // give 10 seconds to program
    ulProgramModeExitTime = millis() + 10000;
    gMode = MODE_PROGRAM;
 
    unThrottleCenter = unThrottleIn;
    unSteeringCenter = unSteeringIn;
   
    unThrottleMin = RC_NEUTRAL;
    unThrottleMax = RC_NEUTRAL;
    unThrottleMin = RC_NEUTRAL;
    unThrottleMax = RC_NEUTRAL;
   
    gDirection = DIRECTION_STOP;
   
    delay(20);
  }


The rest of the loop function implements two modes 1) MODE_RUN and 2) MODE_PROGRAM. In MODE_PROGRAM, we monitor the incoming throttle and steering signals and test them to see whether they represent new end points, if so we update the current end points to the new values. The end points are recorded in unThrottleMin, unThrottleMax, unSteeringMin and unSteeringMax.

We also check whether we have reached ulProgramModeExitTime if so we store the new end points in EEPROM and set gMode back to MODE_RUN.


  if(gMode == MODE_PROGRAM)
  {
   if(ulProgramModeExitTime < millis())
   {
     // set to 0 and exit program mode
     ulProgramModeExitTime = 0;
     gMode = MODE_RUN;
   }
  
   if(unThrottleIn > unThrottleMax && unThrottleIn <= RC_MAX)
   {
     unThrottleMax = unThrottleIn;
   }
   else if(unThrottleIn < unThrottleMin && unThrottleIn >= RC_MIN)
   {
     unThrottleMin = unThrottleIn;
   }
  
   if(unSteeringIn > unSteeringMax && unSteeringIn <= RC_MAX)
   {
     unSteeringMax = unSteeringIn;
   }
   else if(unSteeringIn < unSteeringMin && unSteeringIn >= RC_MIN)
   {
     unSteeringMin = unSteeringIn;
   }
  }

Now that the calibration is covered we can move on to the fun part - controlling the motors.

Controlling Two Tracked Motors With An RC Transmitter.

In order to control a track vehicle with a standard RC Transmitter and receiver we need a way of converting from throttle and steering channels into two throttle channels and no steering channel.

In practice its very simple and can be outlined as follows -

1) Read the throttle channel and set the left and right motor speeds to the same value based on the level of input.
2) Read the steering channel, if the steering is outside of a central deadband, reduce the speed of the motor on the inside of the required direction in proportion to the level of steering input.

If the user turns the transmitter wheel 20% to the left, we will slow the left track down by 20% causing the truck to turn to the left.

It gets a little more complicated when we bring forwards and reverse into the mix and a little more complicated again when we introduce an ability to turn on the spot using counter rotation of the two motors  when steering is applied at idle throttle.

In order to manage these additional requirements I have added direction and gear variables. The direction variable is initially set based on throttle input - FORWARDS or REVERSE. The gear variable is also throttle dependent, if the throttle is within the central dead band, the gear is set to IDLE, if it is outside the deadband, the gear is set to FULL. 

Steering

The next section of code looks at the steering channel. If the gear has been set to IDLE and a steering angle is applied, the direction is overridden and set to ROTATE, this allows the truck to turn on the spot at idle. If the gear is FULL, the direction is not overridden, but the speed of the inside track is reduced in proportion to the level of steering.

In the case of 100% left or right steering input, the inside track will be stopped completely allowing the truck to pivot in a sharp turn around the inside track.

Rotation On The Spot At Idle -
// if at idle, set the direction to DIRECTION_ROTATE_RIGHT or DIRECTION_ROTATE_LEFT
// Speed of rotation is proportional to steering angle

     case GEAR_IDLE:
        if(unSteeringIn > (unSteeringCenter + RC_DEADBAND))
        {
          gDirection = DIRECTION_ROTATE_RIGHT;
          // use steering to set throttle
          throttleRight = throttleLeft = map(unSteeringIn,unSteeringCenter,unSteeringMax,PWM_MIN,PWM_MAX);
        }
        else if(unSteeringIn < (unSteeringCenter - RC_DEADBAND))
        {
          gDirection = DIRECTION_ROTATE_LEFT;
          // use steering to set throttle
          throttleRight = throttleLeft = map(unSteeringIn,unSteeringMin,unSteeringCenter,PWM_MAX,PWM_MIN);
        }
        break;
      

Proportional Steering During Forwards Or Reverse Motion

      // if not at idle proportionally restrain inside track to turn vehicle around it
      case GEAR_FULL:
        if(unSteeringIn > (unSteeringCenter + RC_DEADBAND))
        {
          throttleRight = map(unSteeringIn,unSteeringCenter,unSteeringMax,gThrottle,PWM_MIN);
        }
        else if(unSteeringIn < (unSteeringCenter - RC_DEADBAND))
        {
          throttleLeft = map(unSteeringIn,unSteeringMin,unSteeringCenter,PWM_MIN,gThrottle);
        }
        break;
      

In the proportional steering mode, the map function is used to convert from steering input to a value determined by both the steering input and the throttle input. This is achieved in a single step by including the throttle input variable gThrottle in the output range passed to 'map'. This results in an output that is proportional to both the steering input unSteeringIn and the throttle input gThrottle.


In the next section of code, the L293 logic pins are set based on direction, this sets the required direction of rotation for each of the two motors.

At the end of this section analogWrite is used to set the individual PWM speeds or the two independent motors.


  if((gDirection != gOldDirection) || (gGear != gOldGear))
  {
    gOldDirection = gDirection;
    gOldGear = gGear;

    digitalWrite(LEFT1,LOW);
    digitalWrite(LEFT2,LOW);
    digitalWrite(RIGHT1,LOW);
    digitalWrite(RIGHT2,LOW);

    switch(gDirection)
    {
    case DIRECTION_FORWARD:
      digitalWrite(LEFT1,LOW);
      digitalWrite(LEFT2,HIGH);
      digitalWrite(RIGHT1,LOW);
      digitalWrite(RIGHT2,HIGH);
      break;
    case DIRECTION_REVERSE:
      digitalWrite(LEFT1,HIGH);
      digitalWrite(LEFT2,LOW);
      digitalWrite(RIGHT1,HIGH);
      digitalWrite(RIGHT2,LOW);
      break;
    case DIRECTION_ROTATE_LEFT:
      digitalWrite(LEFT1,HIGH);
      digitalWrite(LEFT2,LOW);
      digitalWrite(RIGHT1,LOW);
      digitalWrite(RIGHT2,HIGH);
      break;
    case DIRECTION_ROTATE_RIGHT:
      digitalWrite(LEFT1,LOW);
      digitalWrite(LEFT2,HIGH);
      digitalWrite(RIGHT1,HIGH);
      digitalWrite(RIGHT2,LOW);
      break;
    case DIRECTION_STOP:
      digitalWrite(LEFT1,LOW);
      digitalWrite(LEFT2,LOW);
      digitalWrite(RIGHT1,LOW);
      digitalWrite(RIGHT2,LOW);
      break;
    }
  }
 

The code presented provides us with full proportional forwards and reverse speed, left and right steering at any speed and in any direction and an extra bonus of on the spot rotation in either direction at idle.

The full code -

Enjoy

Duane B


#include <EEPROM.h>

// MultiChannel L293D
//
// rcarduino.blogspot.com
//
// A simple approach for reading two RC Channels from a hobby quality receiver
// and outputting to the common motor driver IC the L293D to drive a tracked vehicle
//
// We will use the Arduino to mix the channels to give car like steering using a standard two stick
// or pistol grip transmitter. The Aux channel will be used to switch and optional momentum mode on and off
//
// See related posts -
//
// Reading an RC Receiver - What does this signal look like and how do we read it -
// http://rcarduino.blogspot.co.uk/2012/01/how-to-read-rc-receiver-with.html
//
// The Arduino library only supports two interrupts, the Arduino pinChangeInt Library supports more than 20 -
// http://rcarduino.blogspot.co.uk/2012/03/need-more-interrupts-to-read-more.html
//
// The Arduino Servo Library supports upto 12 Servos on a single Arduino, read all about it here -
// http://rcarduino.blogspot.co.uk/2012/01/can-i-control-more-than-x-servos-with.html
//
// The wrong and then the right way to connect servos to Arduino
// http://rcarduino.blogspot.com/2012/04/servo-problems-with-arduino-part-1.html
// http://rcarduino.blogspot.com/2012/04/servo-problems-part-2-demonstration.html
//
// Using pinChangeInt library and Servo library to read three RC Channels and drive 3 RC outputs (mix of Servos and ESCs)
// http://rcarduino.blogspot.com/2012/04/how-to-read-multiple-rc-channels-draft.html
//
// rcarduino.blogspot.com
//

// if stopped and turn
// rotate on spot
// if crawling
// rotate on one side
// if forward or backward
// map

#define RC_NEUTRAL 1500
#define RC_MAX 2000
#define RC_MIN 1000
#define RC_DEADBAND 40

uint16_t unSteeringMin = RC_MIN;
uint16_t unSteeringMax = RC_MAX;
uint16_t unSteeringCenter = RC_NEUTRAL;

uint16_t unThrottleMin = RC_MIN;
uint16_t unThrottleMax = RC_MAX;
uint16_t unThrottleCenter = RC_NEUTRAL;

#define PWM_MIN 0
#define PWM_MAX 255

#define GEAR_NONE 1
#define GEAR_IDLE 1
#define GEAR_FULL 2

#define PWM_SPEED_LEFT 10
#define PWM_SPEED_RIGHT 11
#define LEFT1 5
#define LEFT2 6
#define RIGHT1 7
#define RIGHT2 8

#define PROGRAM_PIN 9

// Assign your channel in pins
#define THROTTLE_IN_PIN 2
#define STEERING_IN_PIN 3

// These bit flags are set in bUpdateFlagsShared to indicate which
// channels have new signals
#define THROTTLE_FLAG 1
#define STEERING_FLAG 2

// holds the update flags defined above
volatile uint8_t bUpdateFlagsShared;

// shared variables are updated by the ISR and read by loop.
// In loop we immediatley take local copies so that the ISR can keep ownership of the
// shared ones. To access these in loop
// we first turn interrupts off with noInterrupts
// we take a copy to use in loop and the turn interrupts back on
// as quickly as possible, this ensures that we are always able to receive new signals
volatile uint16_t unThrottleInShared;
volatile uint16_t unSteeringInShared;

// These are used to record the rising edge of a pulse in the calcInput functions
// They do not need to be volatile as they are only used in the ISR. If we wanted
// to refer to these in loop and the ISR then they would need to be declared volatile
uint32_t ulThrottleStart;
uint32_t ulSteeringStart;

uint8_t gThrottle = 0;
uint8_t gGear = GEAR_NONE;
uint8_t gOldGear = GEAR_NONE;

#define DIRECTION_STOP 0
#define DIRECTION_FORWARD 1
#define DIRECTION_REVERSE 2
#define DIRECTION_ROTATE_RIGHT 3
#define DIRECTION_ROTATE_LEFT 4

uint8_t gThrottleDirection = DIRECTION_STOP;
uint8_t gDirection = DIRECTION_STOP;
uint8_t gOldDirection = DIRECTION_STOP;

#define IDLE_MAX 80

#define MODE_RUN 0
#define MODE_PROGRAM 1

uint8_t gMode = MODE_RUN;
uint32_t ulProgramModeExitTime = 0;

// Index into the EEPROM Storage assuming a 0 based array of uint16_t
// Data to be stored low byte, high byte
#define EEPROM_INDEX_STEERING_MIN 0
#define EEPROM_INDEX_STEERING_MAX 1
#define EEPROM_INDEX_STEERING_CENTER 2
#define EEPROM_INDEX_THROTTLE_MIN 3
#define EEPROM_INDEX_THROTTLE_MAX 4
#define EEPROM_INDEX_THROTTLE_CENTER 5

void setup()
{
  Serial.begin(9600);

  Serial.println("RCChannelsTo293");

  attachInterrupt(0 /* INT0 = THROTTLE_IN_PIN */,calcThrottle,CHANGE);
  attachInterrupt(1 /* INT1 = STEERING_IN_PIN */,calcSteering,CHANGE);

  pinMode(PWM_SPEED_LEFT,OUTPUT);
  pinMode(PWM_SPEED_RIGHT,OUTPUT);
  pinMode(LEFT1,OUTPUT);
  pinMode(LEFT2,OUTPUT);
  pinMode(RIGHT1,OUTPUT);
  pinMode(RIGHT2,OUTPUT);
 
  pinMode(PROGRAM_PIN,INPUT);
 
  readSettingsFromEEPROM();
}

void loop()
{
  // create local variables to hold a local copies of the channel inputs
  // these are declared static so that thier values will be retained
  // between calls to loop.
  static uint16_t unThrottleIn;
  static uint16_t unSteeringIn;
  // local copy of update flags
  static uint8_t bUpdateFlags;

  // check shared update flags to see if any channels have a new signal
  if(bUpdateFlagsShared)
  {
    noInterrupts(); // turn interrupts off quickly while we take local copies of the shared variables

      // take a local copy of which channels were updated in case we need to use this in the rest of loop
    bUpdateFlags = bUpdateFlagsShared;

    // in the current code, the shared values are always populated
    // so we could copy them without testing the flags
    // however in the future this could change, so lets
    // only copy when the flags tell us we can.

    if(bUpdateFlags & THROTTLE_FLAG)
    {
      unThrottleIn = unThrottleInShared;
    }

    if(bUpdateFlags & STEERING_FLAG)
    {
      unSteeringIn = unSteeringInShared;
    }

    // clear shared copy of updated flags as we have already taken the updates
    // we still have a local copy if we need to use it in bUpdateFlags
    bUpdateFlagsShared = 0;

    interrupts(); // we have local copies of the inputs, so now we can turn interrupts back on
    // as soon as interrupts are back on, we can no longer use the shared copies, the interrupt
    // service routines own these and could update them at any time. During the update, the
    // shared copies may contain junk. Luckily we have our local copies to work with :-)
  }

  if(false == digitalRead(PROGRAM_PIN))
  {
    // give 10 seconds to program
    ulProgramModeExitTime = millis() + 10000;
    gMode = MODE_PROGRAM;
   
    unThrottleMin = RC_NEUTRAL;
    unThrottleMax = RC_NEUTRAL;
    unSteeringMin = RC_NEUTRAL;
    unSteeringMax = RC_NEUTRAL;
   
    unThrottleCenter = unThrottleIn;
    unSteeringCenter = unSteeringIn;
   
    gDirection = DIRECTION_STOP;
   
    delay(20);
  }
 
  if(gMode == MODE_PROGRAM)
  {
   if(ulProgramModeExitTime < millis())
   {
     // set to 0 to exit program mode
     ulProgramModeExitTime = 0;
     gMode = MODE_RUN;
    
     writeSettingsToEEPROM();
   }
   else
   {
     if(unThrottleIn > unThrottleMax && unThrottleIn <= RC_MAX)
     {
       unThrottleMax = unThrottleIn;
     }
     else if(unThrottleIn < unThrottleMin && unThrottleIn >= RC_MIN)
     {
       unThrottleMin = unThrottleIn;
     }
    
     if(unSteeringIn > unSteeringMax && unSteeringIn <= RC_MAX)
     {
       unSteeringMax = unSteeringIn;
     }
     else if(unSteeringIn < unSteeringMin && unSteeringIn >= RC_MIN)
     {
       unSteeringMin = unSteeringIn;
     }
   }
  }

  // do any processing from here onwards
  // only use the local values unAuxIn, unThrottleIn and unSteeringIn, the shared
  // variables unAuxInShared, unThrottleInShared, unSteeringInShared are always owned by
  // the interrupt routines and should not be used in loop
 
  if(gMode == MODE_RUN)
  {
    // we are checking to see if the channel value has changed, this is indicated
    // by the flags. For the simple pass through we don't really need this check,
    // but for a more complex project where a new signal requires significant processing
    // this allows us to only calculate new values when we have new inputs, rather than
    // on every cycle.
    if(bUpdateFlags & THROTTLE_FLAG)
    {
      // A good idea would be to check the before and after value,
      // if they are not equal we are receiving out of range signals
      // this could be an error, interference or a transmitter setting change
      // in any case its a good idea to at least flag it to the user somehow
      unThrottleIn = constrain(unThrottleIn,unThrottleMin,unThrottleMax);
     
      if(unThrottleIn > unThrottleCenter)
      {
        gThrottle = map(unThrottleIn,unThrottleCenter,unThrottleMax,PWM_MIN,PWM_MAX);
        gThrottleDirection = DIRECTION_FORWARD;
      }
      else
      {
        gThrottle = map(unThrottleIn,unThrottleMin,unThrottleCenter,PWM_MAX,PWM_MIN);
        gThrottleDirection = DIRECTION_REVERSE;
      }
 
      if(gThrottle < IDLE_MAX)
      {
        gGear = GEAR_IDLE;
      }
      else
      {
        gGear = GEAR_FULL;
      }
    }
 
    if(bUpdateFlags & STEERING_FLAG)
    {
      uint8_t throttleLeft = gThrottle;
      uint8_t throttleRight = gThrottle;
 
      gDirection = gThrottleDirection;
     
      // see previous comments regarding trapping out of range errors
      // this is left for the user to decide how to handle and flag
      unSteeringIn = constrain(unSteeringIn,unSteeringMin,unSteeringMax);
 
      // if idle spin on spot
      switch(gGear)
      {
      case GEAR_IDLE:
        if(unSteeringIn > (unSteeringCenter + RC_DEADBAND))
        {
          gDirection = DIRECTION_ROTATE_RIGHT;
          // use steering to set throttle
          throttleRight = throttleLeft = map(unSteeringIn,unSteeringCenter,unSteeringMax,PWM_MIN,PWM_MAX);
        }
        else if(unSteeringIn < (unSteeringCenter - RC_DEADBAND))
        {
          gDirection = DIRECTION_ROTATE_LEFT;
          // use steering to set throttle
          throttleRight = throttleLeft = map(unSteeringIn,unSteeringMin,unSteeringCenter,PWM_MAX,PWM_MIN);
        }
        break;
      // if not idle proportionally restrain inside track to turn vehicle around it
      case GEAR_FULL:
        if(unSteeringIn > (unSteeringCenter + RC_DEADBAND))
        {
          throttleRight = map(unSteeringIn,unSteeringCenter,unSteeringMax,gThrottle,PWM_MIN);
        }
        else if(unSteeringIn < (unSteeringCenter - RC_DEADBAND))
        {
          throttleLeft = map(unSteeringIn,unSteeringMin,unSteeringCenter,PWM_MIN,gThrottle);
        }
        break;
      }
      analogWrite(PWM_SPEED_LEFT,throttleLeft);
      analogWrite(PWM_SPEED_RIGHT,throttleRight);
    }
  }
 
  if((gDirection != gOldDirection) || (gGear != gOldGear))
  {
    gOldDirection = gDirection;
    gOldGear = gGear;

    digitalWrite(LEFT1,LOW);
    digitalWrite(LEFT2,LOW);
    digitalWrite(RIGHT1,LOW);
    digitalWrite(RIGHT2,LOW);

    switch(gDirection)
    {
    case DIRECTION_FORWARD:
      digitalWrite(LEFT1,LOW);
      digitalWrite(LEFT2,HIGH);
      digitalWrite(RIGHT1,LOW);
      digitalWrite(RIGHT2,HIGH);
      break;
    case DIRECTION_REVERSE:
      digitalWrite(LEFT1,HIGH);
      digitalWrite(LEFT2,LOW);
      digitalWrite(RIGHT1,HIGH);
      digitalWrite(RIGHT2,LOW);
      break;
    case DIRECTION_ROTATE_LEFT:
      digitalWrite(LEFT1,HIGH);
      digitalWrite(LEFT2,LOW);
      digitalWrite(RIGHT1,LOW);
      digitalWrite(RIGHT2,HIGH);
      break;
    case DIRECTION_ROTATE_RIGHT:
      digitalWrite(LEFT1,LOW);
      digitalWrite(LEFT2,HIGH);
      digitalWrite(RIGHT1,HIGH);
      digitalWrite(RIGHT2,LOW);
      break;
    case DIRECTION_STOP:
      digitalWrite(LEFT1,LOW);
      digitalWrite(LEFT2,LOW);
      digitalWrite(RIGHT1,LOW);
      digitalWrite(RIGHT2,LOW);
      break;
    }
  }

  bUpdateFlags = 0;
}


// simple interrupt service routine
void calcThrottle()
{
  // if the pin is high, its a rising edge of the signal pulse, so lets record its value
  if(digitalRead(THROTTLE_IN_PIN) == HIGH)
  {
    ulThrottleStart = micros();
  }
  else
  {
    // else it must be a falling edge, so lets get the time and subtract the time of the rising edge
    // this gives use the time between the rising and falling edges i.e. the pulse duration.
    unThrottleInShared = (uint16_t)(micros() - ulThrottleStart);
    // use set the throttle flag to indicate that a new throttle signal has been received
    bUpdateFlagsShared |= THROTTLE_FLAG;
  }
}

void calcSteering()
{
  if(digitalRead(STEERING_IN_PIN) == HIGH)
  {
    ulSteeringStart = micros();
  }
  else
  {
    unSteeringInShared = (uint16_t)(micros() - ulSteeringStart);
    bUpdateFlagsShared |= STEERING_FLAG;
  }
}




// Updated 04/06/2012 to use default values if no previous calibration is stored in EEPROM

void readSettingsFromEEPROM()
{
  unSteeringMin = readChannelSetting(EEPROM_INDEX_STEERING_MIN);
  if(unSteeringMin < RC_MIN || unSteeringMin > RC_NEUTRAL)
  {
    unSteeringMin = RC_MIN;
  }
  Serial.println(unSteeringMin);

  unSteeringMax = readChannelSetting(EEPROM_INDEX_STEERING_MAX);
  if(unSteeringMax > RC_MAX || unSteeringMax < RC_NEUTRAL)
  {
    unSteeringMax = RC_MAX;
  }
  Serial.println(unSteeringMax);
 
  unSteeringCenter = readChannelSetting(EEPROM_INDEX_STEERING_CENTER);
  if(unSteeringCenter < unSteeringMin || unSteeringCenter > unSteeringMax)
  {
    unSteeringCenter = RC_NEUTRAL;
  }
  Serial.println(unSteeringCenter);

  unThrottleMin = readChannelSetting(EEPROM_INDEX_THROTTLE_MIN);
  if(unThrottleMin < RC_MIN || unThrottleMin > RC_NEUTRAL)
  {
    unThrottleMin = RC_MIN;
  }
  Serial.println(unThrottleMin);

  unThrottleMax = readChannelSetting(EEPROM_INDEX_THROTTLE_MAX);
  if(unThrottleMax > RC_MAX || unThrottleMax < RC_NEUTRAL)
  {
    unThrottleMax = RC_MAX;
  }
  Serial.println(unThrottleMax);
 
  unThrottleCenter = readChannelSetting(EEPROM_INDEX_THROTTLE_CENTER);
  if(unThrottleCenter < unThrottleMin || unThrottleCenter > unThrottleMax)
  {
    unThrottleCenter = RC_NEUTRAL;
  }
  Serial.println(unThrottleCenter);
}

void writeSettingsToEEPROM()
{
  writeChannelSetting(EEPROM_INDEX_STEERING_MIN,unSteeringMin);
  writeChannelSetting(EEPROM_INDEX_STEERING_MAX,unSteeringMax);
  writeChannelSetting(EEPROM_INDEX_STEERING_CENTER,unSteeringCenter);
  writeChannelSetting(EEPROM_INDEX_THROTTLE_MIN,unThrottleMin);
  writeChannelSetting(EEPROM_INDEX_THROTTLE_MAX,unThrottleMax);
  writeChannelSetting(EEPROM_INDEX_THROTTLE_CENTER,unThrottleCenter);
           
  Serial.println(unSteeringMin);
  Serial.println(unSteeringMax);
  Serial.println(unSteeringCenter);
  Serial.println(unThrottleMin);
  Serial.println(unThrottleMax);
  Serial.println(unThrottleCenter);
}


uint16_t readChannelSetting(uint8_t nStart)
{
  uint16_t unSetting = (EEPROM.read((nStart*sizeof(uint16_t))+1)<<8);
  unSetting += EEPROM.read(nStart*sizeof(uint16_t));

  return unSetting;
}

void writeChannelSetting(uint8_t nIndex,uint16_t unSetting)
{
  EEPROM.write(nIndex*sizeof(uint16_t),lowByte(unSetting));
  EEPROM.write((nIndex*sizeof(uint16_t))+1,highByte(unSetting));
}





Wednesday, May 16, 2012

RC Arduino Robot


A low cost remote controlled robot using a standalone Arduino to interface between a pistol grip RC Transmitter/Receiver and an L293DNE H-Bridge Motor driver. The project provides three mapping/mixing modes between the pistol grip transmitters channels and the forwards and reverse operation of the robot tracks. The mapping mode is dependent on the throttle input as follows - 

The Arduino provides three steering modes depending on the level of throttle input. The modes listed below are shown in the order of throttle input (low to high) and the order in which they appear in the video.

Mode 1 - Opposition
When the throttle is near the idle point, the tracks will operate in opposition to turn the robot on the spot.

Mode 2 - Braking
At low speed the robot turns by locking the inside track and pivoting around it.

Mode 3 - Proportional Control
At higher speeds the robot has full proportional control allowing for fine control over the steering at speed.

All modes are available in forwards and reverse, speed of rotation and forwards/reverse motion is also proportional in all modes.


The chassis consists of components from the the following Tamiya parts sets -


Double Independent Gearbox - 70168
http://www.etamiya.com/shop/tamiya-70168-tamiya-double-gear-leftriight-independent-speed-p-6477.html

Track and Wheel Set - 70100
http://www.etamiya.com/shop/tamiya-70100-tamiya-track-wheel-p-5767.html

Universal Plate Set - 70157
http://www.etamiya.com/shop/tamiya-70157-tamiya-universal-plate-2pcs-p-6911.html


Chassis underside view
Very few parts are used from 70157, any flat material could be substituted. 
For anyone planning to use 70157 or similar products I strongly recommend using 3mm machine screws and nylock nuts in place of the fixing pins provided in these sets. Nylon locking nuts are widely used in RC Cars to prevent parts unscrewing when subjected to vibration.

3mm locking nuts -
http://www.rcmart.com/traxxas-2745-nylon-locking-nuts-p-32138.html?cPath=595_739_331

Prototyping Platform
As I had not worked with an L293DNE motor driver before I wanted to build a circuit which I could use for prototyping. To do this I built a simple stripboard circuit with a standalone Arduino on the left and the L293DNE on the right.

To connect the two I soldered in several sets of headers allowing me to access the Arduino pins and the key L293DNE pins with jumper wires. While the initial result looked very promising as a prototyping platform, the end result is less appealing -

Initial Prototyping Platform
The End Result As Used In the Video
If I was to build the circuit again I would plan in advance for full forwards, full reverse and neutral throttle indicator LEDs. I have also added a programming button, this puts the robot into a programming mode where it will monitor the receiver for the maximum and minimum end points on the steering and throttle channels for ten seconds. These are used during normal operation to calculate the proportional output signal to the L293DNE motor driver based on the input from the receiver.

 The Robot next to the Spectrum DX3S Transmitter used to control it.

More about the transmitter here -  

I had originally intended to build a styrene Armoured Personnel Carrier type body for the project however my two year old and four year old were so dismissive of the paper prototype in the video that I may just build a Lego adaptor plate and let them build and rebuild as many bodies as they like.

Power
The Standalone Arduino is powered by a PP3 9 Volt battery mounted under the chassis plate. The motors and L293DNE are powered by 4AA batteries mounted above the chassis plate and just visible under the prototyping board in the picture.

Why two sets of batteries ? See here - 

The Code
The code builds on the preceding series of posts on this blog dealing with interface a micro controller to an RC Receiver. Most posts in the series have assumed that the Arduino will read the incoming RC Signals, transform them and output them as new RC Signals using the Servo library. In this case we are doing something slightly different.

The Spectrum DX3S transmitter is a pistol grip type with a trigger based throttle channel and a wheel based steering channel. These are not the most intuitive controls for a tracked vehicle having only forwards and backwards control over its two tracks. In this project, the Arduino is used to map from the transmitter input to independent instructions to the two motors to produce the desired movement.

In order to make the project a little more interesting I want to have three modes of movement 1) Turning on the spot, 2) Locking a track to pivot about it 3) Proportional power to each track for smooth steering. The mode is automatically selected based on the throttle input. At a standstill, the vehicle will operate both tracks in opposite directions to turn on the spot. At low speeds it will lock the inside track and pivot around it, at higher speeds the vehicle turns through proportionally slowing down the inside track depending on the degree of steering input.

Full code and explanation here -

Note - The final project has only modes 1) and 3), mode 2) has been removed as it provided no additional functionality, it is possible to lock the inside track for tight turns by applying full steering in mode 3.

http://rcarduino.blogspot.com/2012/05/interfacing-rc-channels-to-l293d-motor.html















Friday, May 11, 2012

Lap Timer Preview

Video 1 - Lap Review Mode

A quick tour through part of the menu system. Session summaries with best and average lap times, select a session to review the laps within the session.



Its very simple interface, ok to enter a mode, cancel to exit a mode and up/down to cycle through any options in a mode.

Video 2 - Daylight Laps




One of the challenges with using infra red for lap timing is that daylight will easily saturate the detectors rending them useless. My solution to this is to enclose the detector in a shade however even this isn't enough. To get reliable lap detection with no false laps I have painted the inside of the detector enclosure with 'ultra flat' paint.

The particular paint I have used is manufactured by Krylon and is targeted at hunters, paintballers and airsoft players that want maximum camouflage with no reflection from their equipment. The ability of this paint to suppress reflection stops any daylight from getting to the back of the enclosure. The only light that can reach the detector at the back of the enclosure is light directed directly at it, the light from a lapping car.



Test Car

Tamiya M03 Mini fitted with a Tamiya Sport Tuned motor and good for around 40Km/h.

The lap timer should be good for full size race car speeds, I plan to test at 120Km/h in the next day or two using my daily driver and a long stretch of empty road.

For race car and Kart speeds I will see who I can persuade to test the system at the Dubai Autodrome.


Inside The Lap Timer

Keeping the cost down.

A standalone Arduino, an LCD screen and not too much else.

Small enough to fit to the steering wheel of a Kart.









More soon...

Duane B



Wednesday, May 9, 2012

Personal Lap Timer - Countdown to launch

The Arduino side of the personal lap timer is finished, all that remains to do before I can launch the project is to produce parts lists and schematics. I am also changing the transponder design slightly to allow for a low power and high power option. The low power option is for use in scale model racing where the track is narrow and will often loop back on itself. The high power option allows the lap timer to be used in Karts or Automobiles where the track width is much greater and a more powerful signal is needed.


I hope to be able to provide some videos of the timer in use at local RC, Kart and Automobile tracks over the next week or two.

I am also looking for an established electronics retailer that would be willing to provide all of the parts required as a prepackaged self assembly 'parts pack'.

The final design is very simple and could be built by anyone with soldering experience. The low parts count keeps the cost and complexity down.


Specifications - 
  • The system records sessions upto 254 laps long and upto 510 laps in total.
  • Each lap is captured automatically by sensing the coded signal generated by the transponder
  • During a lap the current duration is displayed and updated with each second.
  • On completing a lap, the buzzer will sound once, the lap time will be displayed for two seconds
  • In the event that a new fastest lap is recorded, this will be displayed and the buzzer will sound twice
  • The current fastest lap for the session is always displayed in the top row of the screen.
  • When a session is finished, the session review mode provides session summary information including the ability to scroll through all recorded sessions viewing the average and best lap times.
  • From the session review mode a lap review mode can be entered to scroll through the individual lap times within the session.
Stay tuned, more soon ...

Duane B