RCArduinoYawControl by DuaneB is licensed under a Creative Commons Attribution-NonCommercial-ShareAlike 3.0 Unported License.
Based on a work at rcarduino.blogspot.com.
Do you have an RC Car thats just too unpredictable to really enjoy ?
Are you a beginner driver in the rear wheel drive classes and could use some help ?
Do you race in a class where electronic assistance is allowed ?
Existing solutions are not helping you as they fail to address the root cause of RC Car instability.
Race orientated RC Cars are powerful enough to reach scale speeds of 600 miles per hour. Stability solutions currently available try to address this excess power by actively steering into skids however this approach cannot hope to match up to the vast amounts of power resulting in frustration, broken cars and lost interest.
The RCArduino solution is the first complete solution to RC Car yaw control and provides the perfect introduction to driving the fastest and most challenging RC Race cars -
- Learn to drive high powered RC Cars using the RCArduino adjustable assistance system.
- Bring the fun back into high powered RC
- Reduce the sensitivity as your skill level increases.
- Avoid unecessary crashes and breakage while learning
40Km/h Arduino -Passing The Controls Over To Get Feedback From Other Track users
The Project
In Yaw Control Part 1 I discussed how gyroscopes can be applied in Radio Controlled cars to reduce yaw under braking and acceleration.
Since this first post I have developed an Arduino based yaw control system which goes beyond the original goals to address the major flaw in the gyro based approach.
Anti-Yaw Control Part 1 - A Flawed Approach
Background - Why do we need Yaw Control ?
Radio controlled cars have many times the power to weight ratio of conventional cars. In front wheel drive and four wheel drive RC Cars this can be seen in the form of wheel spin and power slides. Few of the rear wheel drive RC Car designs are able to cope with this excess power resulting in a car that spins out under acceleration. All of my RWD Cars - Tamiya M04, F103GT, 3Racing F109 and Sand Scorcher will spin out under modest acceleration.
A similar problem exists with braking, in a RWD RC Car, the motor provides braking, but as the motor is only attached to the rear wheels the effect is similar to pulling the handbrake (e-brake) in a road car. Great for j-turns, but its not going to get you around the track very quickly.
The original and flawed concept
My original design was based on an established idea which is to use a RC Helicopter gyroscope to counter steer into a skid before it can develop into a spin. These gyroscopes are readily available and are used in RC Helicopters to automatically increase or decrease the tail rotor speed to compensate for changes in the main rotor speed which would otherwise cause the helicopter to rotate. This type of gyro is known as a rate gyro.
Rate Gryo Fitted To My F103GT RWD RC Race Car
To use a rate gyro in a car, the gyro is connected between the receiver and the steering servo. The gyro listens to the incoming steering signal and generates an output based on this and the rate of rotation. When the model is accelerating or braking with no steering input, the gyro will detect the car starting to rotate and automatically signal the steering servo to steer into the skid and bring it under control.
Sounds good, whats the problem ?
If we go back to the statement under 'Why do we need Yaw Control' -
'Radio controlled cars have many times the power to weight ratio of conventional cars.'
It is fundamentally a power problem. Attempting to address the problem through steering alone will only get us so far.
So what is the solution ?
The solution is to take active control of both steering and throttle channels, this way we can address the original cause of the problem (reduce the excess power) and the resulting effect (steer into the slide before it becomes a spin).
Unfortunately RC Gyros are primarily designed for use in helicopters and so while we can use them to add active counter steer to our cars, they are not able to interface with the throttle channel and are therefore unable to address the root cause of our problem.
Fortunately there is a interesting micro controller project to build this dual channel active control system.
The RCArduino Solution
Note : For a background on the techniques used to read the RC
Receiver, Output the RC Signal and Calibrate with the RC Transmitter refer to the previous RCArduino posts listed below -
http://rcarduino.blogspot.com/2012/01/how-to-read-rc-receiver-with.html
http://rcarduino.blogspot.com/2012/01/how-to-read-rc-receiver-with.html
The RCArduino approach to yaw control implements tuneable control of both the throttle and steering channels. Separate adjustments are provided for each channel ranging from no intervention to very aggressive intervention.
Features -
- One touch calibration
- Fully and independently adjustable throttle intervention
- Fully and independently adjustable steering intervention
- No need to cut or otherwise alter existing connections to your car electronics
- Fail safe mode
- Unique software specifically designed for high powered RC Cars
Version 0.1 - Big, but easy to work on.
How does it work ?
The unit reads the incoming signals and generates corresponding output signals. When the unit detects the car rotating it will calculate an intervention component for the output to reduce the rotation and allow the driver to retain control. The degree of intervention is adjustable from no intervention to very aggressive.
A further adjustment is provided to control the 'throttle intervention recovery period', when this is set to a low value throttle intervention is applied something like and on/off switch, with a higher value throttle intervention fades away over a period of upto 2 seconds providing for a gradual transition from full intervention to full throttle.
The intervention recovery period provides for a tuneable degree of drift. With a long recovery period the car will be very stable through the corner and onto the straight. With a minimal recovery period the throttle channel will be continually 'blipped' throughout the corner and a moderate drift can be maintained. With low recovery periods, transistions can be very aggressive, as soon as the system detects that rotation has stopped it will apply full power, this can happen in the transistion of an S bend or when exiting a corner onto the straight. This is a useful tuning technique for learning where a car can be driven hard and which points on the circuit require a more restrained approach.
Whats coming in version 1.0 ?
Version 1.0 is smaller and adds LED level meters which display -
1) The rotation rate being reported by the gyro
2) The level of steering intervention currently being applied
3) The level of throttle intervention being applied
4) An additional tuning option on the steering channel
5) An additional tuning option for braking
Next Steps -
The system has been road tested on various surfaces and tyre combinations for around 10 hours without any unpredictable behaviour, the next step is to change the motor from the current entry level silver can motor (<>15,000 RPM) to a Sport Tuned Motor (<>22,000 RPM).
Version 0.1 Code - Lots of obvious optimization needed and lacking features being tested in 1.0, but in the interest of sharing, here it is -
#include <Servo.h>
#include <EEPROM.h>
// RCArduinoYawControl
//
// RCArduinoYawControl by DuaneB is licensed under a Creative Commons Attribution-NonCommercial-ShareAlike 3.0 Unported License.
// Based on a work at rcarduino.blogspot.com.
//
// 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
//
// Two channels in
// Two channels out
// One program button
// One throttle intervention LED
// One Steering Intervention LED
// One Steering Sensitivity POT
// One Throttle Sensitivity POT
// One decay/damping POT
#define RC_NEUTRAL 1500
#define RC_MAX 2000
#define RC_MIN 1000
#define RC_DEADBAND 1
#define ROTATION_CENTER 380
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;
uint16_t unRotationCenter = ROTATION_CENTER; // the gyro I am using outputs a center voltage of <> 1.24 volts
// full range is 0 to 2*1.24 = 2.48
// Using the Arduino voltage reference of 3.3 volts gives a center point of (1.24/(3.3/1024)) = 384
// In tests I see 380 so I will use 380 as my default value.
//////////////////////////////////////////////////////////////////
// PIN ASSIGNMENTS
//////////////////////////////////////////////////////////////////
// ANALOG PINS
//////////////////////////////////////////////////////////////////
#define THROTTLE_SENSITIVITY_PIN 0
#define STEERING_SENSITIVITY_PIN 1
#define THROTTLE_DECAY_PIN 2
#define STEERING_DECAY_PIN 3
#define GYRO_PIN 5
//////////////////////////////////////////////////////////////////
// DIGITAL PINS
//////////////////////////////////////////////////////////////////
#define PROGRAM_PIN 9
#define INFORMATION_INDICATOR_PIN 5
#define ERROR_INDICATOR_PIN 6
#define THROTTLE_IN_PIN 2
#define STEERING_IN_PIN 3
#define THROTTLE_OUT_PIN 8
#define STEERING_OUT_PIN 7
// 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;
// used to ensure we are getting regular throttle signals
uint32_t ulLastThrottleIn;
#define MODE_FORCEPROGRAM 0
#define MODE_RUN 1
#define MODE_QUICK_PROGRAM 2
#define MODE_FULL_PROGRAM 3
#define MODE_ERROR 4
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
#define EEPROM_INDEX_ROTATION_CENTER 6
Servo servoThrottle;
Servo servoSteering;
uint16_t unThrottleSensitivity = 0;
uint16_t unSteeringSensitivity = 0;
uint16_t unThrottleDecay = 0;
uint16_t unSteeringDecay = 0;
void setup()
{
Serial.begin(9600);
pinMode(PROGRAM_PIN,INPUT);
pinMode(INFORMATION_INDICATOR_PIN,OUTPUT);
pinMode(ERROR_INDICATOR_PIN,OUTPUT);
attachInterrupt(0 /* INT0 = THROTTLE_IN_PIN */,calcThrottle,CHANGE);
attachInterrupt(1 /* INT1 = STEERING_IN_PIN */,calcSteering,CHANGE);
readAnalogSettings();
servoThrottle.attach(THROTTLE_OUT_PIN);
servoSteering.attach(STEERING_OUT_PIN);
if(false == readSettingsFromEEPROM())
{
gMode = MODE_FORCEPROGRAM;
}
ulLastThrottleIn = millis();
}
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 rotation rate
static uint16_t unRotation;
// local copy of update flags
static uint8_t bUpdateFlags;
static uint16_t unThrottleInterventionPeak;
static uint16_t unSteeringInterventionPeak;
uint32_t ulMillis = millis();
// 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) && gMode != MODE_FULL_PROGRAM)
{
// give 10 seconds to program
gMode = MODE_QUICK_PROGRAM;
// turn indicators off for QUICK PROGRAM mode
digitalWrite(INFORMATION_INDICATOR_PIN,LOW);
digitalWrite(ERROR_INDICATOR_PIN,LOW);
// wait two seconds and test program pin again
// if pin if still held low, enter full program mode
// otherwise read sensitivity pots and return to run
// mode with new sensitivity readings.
delay(2000);
if(false == digitalRead(PROGRAM_PIN))
{
gMode = MODE_FULL_PROGRAM;
ulProgramModeExitTime = ulMillis + 10000;
unThrottleMin = RC_NEUTRAL;
unThrottleMax = RC_NEUTRAL;
unSteeringMin = RC_NEUTRAL;
unSteeringMax = RC_NEUTRAL;
unThrottleCenter = unThrottleIn;
unSteeringCenter = unSteeringIn;
}
else
{
gMode = MODE_RUN;
ulMillis = millis();
ulLastThrottleIn = ulMillis;
}
// Take new sensitivity and decay readings for quick program and full program modes here
readAnalogSettings();
}
if(gMode == MODE_FULL_PROGRAM)
{
if(ulProgramModeExitTime < ulMillis)
{
// set to 0 to exit program mode
ulProgramModeExitTime = 0;
gMode = MODE_RUN;
analogRead(GYRO_PIN);
uint32_t ulTotal = 0;
for(int nCount = 0;nCount < 50;nCount++)
{
ulTotal += analogRead(GYRO_PIN);
}
unRotationCenter = ulTotal/50;
writeSettingsToEEPROM();
ulLastThrottleIn = ulMillis;
}
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;
}
}
}
else if(gMode == MODE_RUN)
{
if((ulLastThrottleIn + 500) < ulMillis)
{
gMode = MODE_ERROR;
}
else
{
// 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)
{
unRotation = analogRead(GYRO_PIN);
}
if(bUpdateFlags & THROTTLE_FLAG)
{
ulLastThrottleIn = ulMillis;
// 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
uint16_t unThrottleIntervention = 0;
if(unRotation != unRotationCenter)
{
uint32_t ulRotationWithGain = 0;
if(unRotation > unRotationCenter)
{
ulRotationWithGain = (long)(unRotation - unRotationCenter)*unThrottleSensitivity;
unThrottleIntervention = map(ulRotationWithGain,0,(long)unRotationCenter*128L,0,500);
}
else
{
ulRotationWithGain = (long)(unRotationCenter - unRotation)*unThrottleSensitivity;
unThrottleIntervention = map(ulRotationWithGain,0,(long)unRotationCenter*128L,0,500);
}
}
if(unThrottleIntervention > unThrottleInterventionPeak)
{
unThrottleInterventionPeak = unThrottleIntervention;
}
else
{
if(unThrottleInterventionPeak >= unThrottleDecay)
{
unThrottleInterventionPeak -= unThrottleDecay;
}
else
{
unThrottleInterventionPeak = 0;
}
if(unThrottleIntervention < unThrottleInterventionPeak)
{
unThrottleIntervention = unThrottleInterventionPeak;
}
}
if(unThrottleIn >= unThrottleCenter)
{
unThrottleIn = constrain(unThrottleIn - unThrottleIntervention,unThrottleCenter,unThrottleIn);
}
else
{
unThrottleIn = constrain(unThrottleIn + unThrottleIntervention,unThrottleMin,unThrottleCenter);
}
servoThrottle.writeMicroseconds(unThrottleIn);
}
}
if(bUpdateFlags & STEERING_FLAG)
{
uint16_t unSteeringIntervention = 0;
uint8_t bInvert = false;
if(unRotation != unRotationCenter)
{
uint32_t ulRotationWithGain = 0;
// note steering offers gain from 0 to 4
uint16_t unInterventionMaxMinusInput = 0;
if(unSteeringIn >= unSteeringCenter)
{
unInterventionMaxMinusInput = (unSteeringMax-unSteeringCenter) - (unSteeringIn - unSteeringCenter);
unInterventionMaxMinusInput = constrain(unInterventionMaxMinusInput,0,unSteeringMax-unSteeringCenter);
}
else
{
unInterventionMaxMinusInput = (unSteeringCenter - unSteeringMin) - (unSteeringCenter - unSteeringIn);
unInterventionMaxMinusInput = constrain(unInterventionMaxMinusInput,0,unSteeringCenter - unSteeringIn);
}
if(unRotation > unRotationCenter)
{
bInvert = true;
ulRotationWithGain = (long)(unRotation - unRotationCenter)*unSteeringSensitivity;
unSteeringIntervention = map(ulRotationWithGain,0,(long)unRotationCenter*128L,0,unInterventionMaxMinusInput);
}
else
{
ulRotationWithGain = (long)(unRotationCenter - unRotation)*unSteeringSensitivity;
unSteeringIntervention = map(ulRotationWithGain,0,(long)unRotationCenter*128L,0,unInterventionMaxMinusInput);
}
}
if(bInvert)
{
unSteeringIn = constrain(unSteeringIn - unSteeringIntervention,unSteeringMin,unSteeringMax);
}
else
{
unSteeringIn = constrain(unSteeringIn + unSteeringIntervention,unSteeringMin,unSteeringMax);
}
servoSteering.writeMicroseconds(unSteeringIn);
}
}
else if(gMode == MODE_ERROR)
{
servoThrottle.writeMicroseconds(unThrottleCenter);
// allow steering to get to safety
if(bUpdateFlags & STEERING_FLAG)
{
unSteeringIn = constrain(unSteeringIn,unSteeringMin,unSteeringMax);
servoSteering.writeMicroseconds(unSteeringIn);
}
}
bUpdateFlags = 0;
animateIndicatorsAccordingToMode(gMode,ulMillis);
}
void animateIndicatorsAccordingToMode(uint8_t gMode,uint32_t ulMillis)
{
static uint32_t ulLastUpdateMillis;
static boolean bAlternate;
if(ulMillis > (ulLastUpdateMillis + 1000))
{
ulLastUpdateMillis = ulMillis;
bAlternate = (!bAlternate);
switch(gMode)
{
// flash alternating info and error once a second
case MODE_FORCEPROGRAM:
digitalWrite(ERROR_INDICATOR_PIN,bAlternate);
digitalWrite(INFORMATION_INDICATOR_PIN,false == bAlternate);
break;
// steady info, turn off error
case MODE_RUN:
digitalWrite(ERROR_INDICATOR_PIN,LOW);
digitalWrite(INFORMATION_INDICATOR_PIN,HIGH);
break;
// flash info once a second, turn off error
case MODE_FULL_PROGRAM:
digitalWrite(INFORMATION_INDICATOR_PIN,bAlternate);
digitalWrite(ERROR_INDICATOR_PIN,LOW);
break;
// alternate error, turn off info
// MODE_QUICK_PROGRAM is self contained and should never get here,
// if it does we have an error.
default:
case MODE_ERROR:
digitalWrite(INFORMATION_INDICATOR_PIN,LOW);
digitalWrite(ERROR_INDICATOR_PIN,bAlternate);
break;
}
}
}
// 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(PIND & 4)
{
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(PIND & 8)
{
ulSteeringStart = micros();
}
else
{
unSteeringInShared = (uint16_t)(micros() - ulSteeringStart);
bUpdateFlagsShared |= STEERING_FLAG;
}
}
uint8_t readSettingsFromEEPROM()
{
uint8_t bError = false;
unSteeringMin = readChannelSetting(EEPROM_INDEX_STEERING_MIN);
if(unSteeringMin < RC_MIN || unSteeringMin > RC_NEUTRAL)
{
unSteeringMin = RC_MIN;
bError = true;
}
Serial.println(unSteeringMin);
unSteeringMax = readChannelSetting(EEPROM_INDEX_STEERING_MAX);
if(unSteeringMax > RC_MAX || unSteeringMax < RC_NEUTRAL)
{
unSteeringMax = RC_MAX;
bError = true;
}
Serial.println(unSteeringMax);
unSteeringCenter = readChannelSetting(EEPROM_INDEX_STEERING_CENTER);
if(unSteeringCenter < unSteeringMin || unSteeringCenter > unSteeringMax)
{
unSteeringCenter = RC_NEUTRAL;
bError = true;
}
Serial.println(unSteeringCenter);
unThrottleMin = readChannelSetting(EEPROM_INDEX_THROTTLE_MIN);
if(unThrottleMin < RC_MIN || unThrottleMin > RC_NEUTRAL)
{
unThrottleMin = RC_MIN;
bError = true;
}
Serial.println(unThrottleMin);
unThrottleMax = readChannelSetting(EEPROM_INDEX_THROTTLE_MAX);
if(unThrottleMax > RC_MAX || unThrottleMax < RC_NEUTRAL)
{
unThrottleMax = RC_MAX;
bError = true;
}
Serial.println(unThrottleMax);
unThrottleCenter = readChannelSetting(EEPROM_INDEX_THROTTLE_CENTER);
if(unThrottleCenter < unThrottleMin || unThrottleCenter > unThrottleMax)
{
unThrottleCenter = RC_NEUTRAL;
bError = true;
}
Serial.println(unThrottleCenter);
unRotationCenter = readChannelSetting(EEPROM_INDEX_ROTATION_CENTER);
Serial.println(unRotationCenter);
// ideally we would have 512 as the center
if(unRotationCenter < 100 || unRotationCenter > 560)
{
unRotationCenter = ROTATION_CENTER;
bError = true;
}
return (false == bError);
}
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);
writeChannelSetting(EEPROM_INDEX_ROTATION_CENTER,unRotationCenter);
Serial.println(unSteeringMin);
Serial.println(unSteeringMax);
Serial.println(unSteeringCenter);
Serial.println(unThrottleMin);
Serial.println(unThrottleMax);
Serial.println(unThrottleCenter);
Serial.println(unRotationCenter);
}
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));
}
/////////////////////////////////////////////////////////////////////////////
//
// The following function reads the analog settings.
// These adjustments are read at startup and anytime that the program button
// is pressed including QUICK_PROGRAM and FULL_PROGRAM
//
// Note the 1-1023 range for sensitivity and 1-100 range for decay 1 = 500/(50*1) per sec = 10 seconds. 100 = 500/(50*100) per sec = .1 seconds
//
/////////////////////////////////////////////////////////////////////////////
void readAnalogSettings()
{
// dummy read to settle ADC
analogRead(THROTTLE_SENSITIVITY_PIN);
unThrottleSensitivity = constrain(analogRead(THROTTLE_SENSITIVITY_PIN),1,1023);
// dummy read to settle ADC
analogRead(STEERING_SENSITIVITY_PIN);
unSteeringSensitivity = constrain(analogRead(STEERING_SENSITIVITY_PIN),1,1023);
// dummy read to settle ADC
analogRead(THROTTLE_DECAY_PIN);
unThrottleDecay = analogRead(THROTTLE_DECAY_PIN);
// if its at the bottom end of the range, turn it off
if(unThrottleDecay <= 50) // instant
{
unThrottleDecay = 500; // = 500/1
}
else if(unThrottleDecay <= 100) // 2 tenths of a second
{
unThrottleDecay = 50; // 2 tenths = (2*(1/10))/(1/50)
}
else if(unThrottleDecay <= 150) // 3 tenths
{
unThrottleDecay = 33;
}
else if(unThrottleDecay <= 200) // 4 tenths
{
unThrottleDecay = 25;
}
else if(unThrottleDecay <= 250) // 5 tenths
{
unThrottleDecay = 20;
}
else if(unThrottleDecay <= 300) // 6 tenths
{
unThrottleDecay = 17;
}
else if(unThrottleDecay <= 350) // 7 tenths
{
unThrottleDecay = 14;
}
else if(unThrottleDecay <= 400) // 8 tenths
{
unThrottleDecay = 12;
}
else if(unThrottleDecay <= 500) // 9 tenths
{
unThrottleDecay = 11;
}
else if(unThrottleDecay <= 600) // 10 tenths
{
unThrottleDecay = 10;
}
else if(unThrottleDecay <= 700) // 11 tenths
{
unThrottleDecay = 9;
}
else if(unThrottleDecay <= 800) // 12 tenths
{
unThrottleDecay = 8;
}
else if(unThrottleDecay <= 850) // 16 tenths
{
unThrottleDecay = 7;
}
else if(unThrottleDecay <= 900) // 2 seconds
{
unThrottleDecay = 5;
}
else if(unThrottleDecay <= 1000)
{
unThrottleDecay = 4;
}
else
{
unThrottleDecay = 1;
}
Serial.println(unThrottleDecay);
// dummy read to settle ADC
analogRead(STEERING_DECAY_PIN);
unSteeringDecay = constrain(analogRead(STEERING_DECAY_PIN),1,500);
}
#include <EEPROM.h>
// RCArduinoYawControl
//
// RCArduinoYawControl by DuaneB is licensed under a Creative Commons Attribution-NonCommercial-ShareAlike 3.0 Unported License.
// Based on a work at rcarduino.blogspot.com.
//
// 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
//
// Two channels in
// Two channels out
// One program button
// One throttle intervention LED
// One Steering Intervention LED
// One Steering Sensitivity POT
// One Throttle Sensitivity POT
// One decay/damping POT
#define RC_NEUTRAL 1500
#define RC_MAX 2000
#define RC_MIN 1000
#define RC_DEADBAND 1
#define ROTATION_CENTER 380
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;
uint16_t unRotationCenter = ROTATION_CENTER; // the gyro I am using outputs a center voltage of <> 1.24 volts
// full range is 0 to 2*1.24 = 2.48
// Using the Arduino voltage reference of 3.3 volts gives a center point of (1.24/(3.3/1024)) = 384
// In tests I see 380 so I will use 380 as my default value.
//////////////////////////////////////////////////////////////////
// PIN ASSIGNMENTS
//////////////////////////////////////////////////////////////////
// ANALOG PINS
//////////////////////////////////////////////////////////////////
#define THROTTLE_SENSITIVITY_PIN 0
#define STEERING_SENSITIVITY_PIN 1
#define THROTTLE_DECAY_PIN 2
#define STEERING_DECAY_PIN 3
#define GYRO_PIN 5
//////////////////////////////////////////////////////////////////
// DIGITAL PINS
//////////////////////////////////////////////////////////////////
#define PROGRAM_PIN 9
#define INFORMATION_INDICATOR_PIN 5
#define ERROR_INDICATOR_PIN 6
#define THROTTLE_IN_PIN 2
#define STEERING_IN_PIN 3
#define THROTTLE_OUT_PIN 8
#define STEERING_OUT_PIN 7
// 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;
// used to ensure we are getting regular throttle signals
uint32_t ulLastThrottleIn;
#define MODE_FORCEPROGRAM 0
#define MODE_RUN 1
#define MODE_QUICK_PROGRAM 2
#define MODE_FULL_PROGRAM 3
#define MODE_ERROR 4
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
#define EEPROM_INDEX_ROTATION_CENTER 6
Servo servoThrottle;
Servo servoSteering;
uint16_t unThrottleSensitivity = 0;
uint16_t unSteeringSensitivity = 0;
uint16_t unThrottleDecay = 0;
uint16_t unSteeringDecay = 0;
void setup()
{
Serial.begin(9600);
pinMode(PROGRAM_PIN,INPUT);
pinMode(INFORMATION_INDICATOR_PIN,OUTPUT);
pinMode(ERROR_INDICATOR_PIN,OUTPUT);
attachInterrupt(0 /* INT0 = THROTTLE_IN_PIN */,calcThrottle,CHANGE);
attachInterrupt(1 /* INT1 = STEERING_IN_PIN */,calcSteering,CHANGE);
readAnalogSettings();
servoThrottle.attach(THROTTLE_OUT_PIN);
servoSteering.attach(STEERING_OUT_PIN);
if(false == readSettingsFromEEPROM())
{
gMode = MODE_FORCEPROGRAM;
}
ulLastThrottleIn = millis();
}
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 rotation rate
static uint16_t unRotation;
// local copy of update flags
static uint8_t bUpdateFlags;
static uint16_t unThrottleInterventionPeak;
static uint16_t unSteeringInterventionPeak;
uint32_t ulMillis = millis();
// 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) && gMode != MODE_FULL_PROGRAM)
{
// give 10 seconds to program
gMode = MODE_QUICK_PROGRAM;
// turn indicators off for QUICK PROGRAM mode
digitalWrite(INFORMATION_INDICATOR_PIN,LOW);
digitalWrite(ERROR_INDICATOR_PIN,LOW);
// wait two seconds and test program pin again
// if pin if still held low, enter full program mode
// otherwise read sensitivity pots and return to run
// mode with new sensitivity readings.
delay(2000);
if(false == digitalRead(PROGRAM_PIN))
{
gMode = MODE_FULL_PROGRAM;
ulProgramModeExitTime = ulMillis + 10000;
unThrottleMin = RC_NEUTRAL;
unThrottleMax = RC_NEUTRAL;
unSteeringMin = RC_NEUTRAL;
unSteeringMax = RC_NEUTRAL;
unThrottleCenter = unThrottleIn;
unSteeringCenter = unSteeringIn;
}
else
{
gMode = MODE_RUN;
ulMillis = millis();
ulLastThrottleIn = ulMillis;
}
// Take new sensitivity and decay readings for quick program and full program modes here
readAnalogSettings();
}
if(gMode == MODE_FULL_PROGRAM)
{
if(ulProgramModeExitTime < ulMillis)
{
// set to 0 to exit program mode
ulProgramModeExitTime = 0;
gMode = MODE_RUN;
analogRead(GYRO_PIN);
uint32_t ulTotal = 0;
for(int nCount = 0;nCount < 50;nCount++)
{
ulTotal += analogRead(GYRO_PIN);
}
unRotationCenter = ulTotal/50;
writeSettingsToEEPROM();
ulLastThrottleIn = ulMillis;
}
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;
}
}
}
else if(gMode == MODE_RUN)
{
if((ulLastThrottleIn + 500) < ulMillis)
{
gMode = MODE_ERROR;
}
else
{
// 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)
{
unRotation = analogRead(GYRO_PIN);
}
if(bUpdateFlags & THROTTLE_FLAG)
{
ulLastThrottleIn = ulMillis;
// 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
uint16_t unThrottleIntervention = 0;
if(unRotation != unRotationCenter)
{
uint32_t ulRotationWithGain = 0;
if(unRotation > unRotationCenter)
{
ulRotationWithGain = (long)(unRotation - unRotationCenter)*unThrottleSensitivity;
unThrottleIntervention = map(ulRotationWithGain,0,(long)unRotationCenter*128L,0,500);
}
else
{
ulRotationWithGain = (long)(unRotationCenter - unRotation)*unThrottleSensitivity;
unThrottleIntervention = map(ulRotationWithGain,0,(long)unRotationCenter*128L,0,500);
}
}
if(unThrottleIntervention > unThrottleInterventionPeak)
{
unThrottleInterventionPeak = unThrottleIntervention;
}
else
{
if(unThrottleInterventionPeak >= unThrottleDecay)
{
unThrottleInterventionPeak -= unThrottleDecay;
}
else
{
unThrottleInterventionPeak = 0;
}
if(unThrottleIntervention < unThrottleInterventionPeak)
{
unThrottleIntervention = unThrottleInterventionPeak;
}
}
if(unThrottleIn >= unThrottleCenter)
{
unThrottleIn = constrain(unThrottleIn - unThrottleIntervention,unThrottleCenter,unThrottleIn);
}
else
{
unThrottleIn = constrain(unThrottleIn + unThrottleIntervention,unThrottleMin,unThrottleCenter);
}
servoThrottle.writeMicroseconds(unThrottleIn);
}
}
if(bUpdateFlags & STEERING_FLAG)
{
uint16_t unSteeringIntervention = 0;
uint8_t bInvert = false;
if(unRotation != unRotationCenter)
{
uint32_t ulRotationWithGain = 0;
// note steering offers gain from 0 to 4
uint16_t unInterventionMaxMinusInput = 0;
if(unSteeringIn >= unSteeringCenter)
{
unInterventionMaxMinusInput = (unSteeringMax-unSteeringCenter) - (unSteeringIn - unSteeringCenter);
unInterventionMaxMinusInput = constrain(unInterventionMaxMinusInput,0,unSteeringMax-unSteeringCenter);
}
else
{
unInterventionMaxMinusInput = (unSteeringCenter - unSteeringMin) - (unSteeringCenter - unSteeringIn);
unInterventionMaxMinusInput = constrain(unInterventionMaxMinusInput,0,unSteeringCenter - unSteeringIn);
}
if(unRotation > unRotationCenter)
{
bInvert = true;
ulRotationWithGain = (long)(unRotation - unRotationCenter)*unSteeringSensitivity;
unSteeringIntervention = map(ulRotationWithGain,0,(long)unRotationCenter*128L,0,unInterventionMaxMinusInput);
}
else
{
ulRotationWithGain = (long)(unRotationCenter - unRotation)*unSteeringSensitivity;
unSteeringIntervention = map(ulRotationWithGain,0,(long)unRotationCenter*128L,0,unInterventionMaxMinusInput);
}
}
if(bInvert)
{
unSteeringIn = constrain(unSteeringIn - unSteeringIntervention,unSteeringMin,unSteeringMax);
}
else
{
unSteeringIn = constrain(unSteeringIn + unSteeringIntervention,unSteeringMin,unSteeringMax);
}
servoSteering.writeMicroseconds(unSteeringIn);
}
}
else if(gMode == MODE_ERROR)
{
servoThrottle.writeMicroseconds(unThrottleCenter);
// allow steering to get to safety
if(bUpdateFlags & STEERING_FLAG)
{
unSteeringIn = constrain(unSteeringIn,unSteeringMin,unSteeringMax);
servoSteering.writeMicroseconds(unSteeringIn);
}
}
bUpdateFlags = 0;
animateIndicatorsAccordingToMode(gMode,ulMillis);
}
void animateIndicatorsAccordingToMode(uint8_t gMode,uint32_t ulMillis)
{
static uint32_t ulLastUpdateMillis;
static boolean bAlternate;
if(ulMillis > (ulLastUpdateMillis + 1000))
{
ulLastUpdateMillis = ulMillis;
bAlternate = (!bAlternate);
switch(gMode)
{
// flash alternating info and error once a second
case MODE_FORCEPROGRAM:
digitalWrite(ERROR_INDICATOR_PIN,bAlternate);
digitalWrite(INFORMATION_INDICATOR_PIN,false == bAlternate);
break;
// steady info, turn off error
case MODE_RUN:
digitalWrite(ERROR_INDICATOR_PIN,LOW);
digitalWrite(INFORMATION_INDICATOR_PIN,HIGH);
break;
// flash info once a second, turn off error
case MODE_FULL_PROGRAM:
digitalWrite(INFORMATION_INDICATOR_PIN,bAlternate);
digitalWrite(ERROR_INDICATOR_PIN,LOW);
break;
// alternate error, turn off info
// MODE_QUICK_PROGRAM is self contained and should never get here,
// if it does we have an error.
default:
case MODE_ERROR:
digitalWrite(INFORMATION_INDICATOR_PIN,LOW);
digitalWrite(ERROR_INDICATOR_PIN,bAlternate);
break;
}
}
}
// 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(PIND & 4)
{
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(PIND & 8)
{
ulSteeringStart = micros();
}
else
{
unSteeringInShared = (uint16_t)(micros() - ulSteeringStart);
bUpdateFlagsShared |= STEERING_FLAG;
}
}
uint8_t readSettingsFromEEPROM()
{
uint8_t bError = false;
unSteeringMin = readChannelSetting(EEPROM_INDEX_STEERING_MIN);
if(unSteeringMin < RC_MIN || unSteeringMin > RC_NEUTRAL)
{
unSteeringMin = RC_MIN;
bError = true;
}
Serial.println(unSteeringMin);
unSteeringMax = readChannelSetting(EEPROM_INDEX_STEERING_MAX);
if(unSteeringMax > RC_MAX || unSteeringMax < RC_NEUTRAL)
{
unSteeringMax = RC_MAX;
bError = true;
}
Serial.println(unSteeringMax);
unSteeringCenter = readChannelSetting(EEPROM_INDEX_STEERING_CENTER);
if(unSteeringCenter < unSteeringMin || unSteeringCenter > unSteeringMax)
{
unSteeringCenter = RC_NEUTRAL;
bError = true;
}
Serial.println(unSteeringCenter);
unThrottleMin = readChannelSetting(EEPROM_INDEX_THROTTLE_MIN);
if(unThrottleMin < RC_MIN || unThrottleMin > RC_NEUTRAL)
{
unThrottleMin = RC_MIN;
bError = true;
}
Serial.println(unThrottleMin);
unThrottleMax = readChannelSetting(EEPROM_INDEX_THROTTLE_MAX);
if(unThrottleMax > RC_MAX || unThrottleMax < RC_NEUTRAL)
{
unThrottleMax = RC_MAX;
bError = true;
}
Serial.println(unThrottleMax);
unThrottleCenter = readChannelSetting(EEPROM_INDEX_THROTTLE_CENTER);
if(unThrottleCenter < unThrottleMin || unThrottleCenter > unThrottleMax)
{
unThrottleCenter = RC_NEUTRAL;
bError = true;
}
Serial.println(unThrottleCenter);
unRotationCenter = readChannelSetting(EEPROM_INDEX_ROTATION_CENTER);
Serial.println(unRotationCenter);
// ideally we would have 512 as the center
if(unRotationCenter < 100 || unRotationCenter > 560)
{
unRotationCenter = ROTATION_CENTER;
bError = true;
}
return (false == bError);
}
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);
writeChannelSetting(EEPROM_INDEX_ROTATION_CENTER,unRotationCenter);
Serial.println(unSteeringMin);
Serial.println(unSteeringMax);
Serial.println(unSteeringCenter);
Serial.println(unThrottleMin);
Serial.println(unThrottleMax);
Serial.println(unThrottleCenter);
Serial.println(unRotationCenter);
}
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));
}
/////////////////////////////////////////////////////////////////////////////
//
// The following function reads the analog settings.
// These adjustments are read at startup and anytime that the program button
// is pressed including QUICK_PROGRAM and FULL_PROGRAM
//
// Note the 1-1023 range for sensitivity and 1-100 range for decay 1 = 500/(50*1) per sec = 10 seconds. 100 = 500/(50*100) per sec = .1 seconds
//
/////////////////////////////////////////////////////////////////////////////
void readAnalogSettings()
{
// dummy read to settle ADC
analogRead(THROTTLE_SENSITIVITY_PIN);
unThrottleSensitivity = constrain(analogRead(THROTTLE_SENSITIVITY_PIN),1,1023);
// dummy read to settle ADC
analogRead(STEERING_SENSITIVITY_PIN);
unSteeringSensitivity = constrain(analogRead(STEERING_SENSITIVITY_PIN),1,1023);
// dummy read to settle ADC
analogRead(THROTTLE_DECAY_PIN);
unThrottleDecay = analogRead(THROTTLE_DECAY_PIN);
// if its at the bottom end of the range, turn it off
if(unThrottleDecay <= 50) // instant
{
unThrottleDecay = 500; // = 500/1
}
else if(unThrottleDecay <= 100) // 2 tenths of a second
{
unThrottleDecay = 50; // 2 tenths = (2*(1/10))/(1/50)
}
else if(unThrottleDecay <= 150) // 3 tenths
{
unThrottleDecay = 33;
}
else if(unThrottleDecay <= 200) // 4 tenths
{
unThrottleDecay = 25;
}
else if(unThrottleDecay <= 250) // 5 tenths
{
unThrottleDecay = 20;
}
else if(unThrottleDecay <= 300) // 6 tenths
{
unThrottleDecay = 17;
}
else if(unThrottleDecay <= 350) // 7 tenths
{
unThrottleDecay = 14;
}
else if(unThrottleDecay <= 400) // 8 tenths
{
unThrottleDecay = 12;
}
else if(unThrottleDecay <= 500) // 9 tenths
{
unThrottleDecay = 11;
}
else if(unThrottleDecay <= 600) // 10 tenths
{
unThrottleDecay = 10;
}
else if(unThrottleDecay <= 700) // 11 tenths
{
unThrottleDecay = 9;
}
else if(unThrottleDecay <= 800) // 12 tenths
{
unThrottleDecay = 8;
}
else if(unThrottleDecay <= 850) // 16 tenths
{
unThrottleDecay = 7;
}
else if(unThrottleDecay <= 900) // 2 seconds
{
unThrottleDecay = 5;
}
else if(unThrottleDecay <= 1000)
{
unThrottleDecay = 4;
}
else
{
unThrottleDecay = 1;
}
Serial.println(unThrottleDecay);
// dummy read to settle ADC
analogRead(STEERING_DECAY_PIN);
unSteeringDecay = constrain(analogRead(STEERING_DECAY_PIN),1,500);
}
Great blog. This make me the wish to do the same work.
ReplyDeleteI have just ordered a flyduino and gyro LPY503AL to do the same work.
I will keep you in touch of the progress.
Regards
Stephane
Very nice! I was thinking of adding something similar to my autonomous car. Did you have trouble with the gyroscope drifting or are you using another sensor like an accelerometer to correct it?
ReplyDeleteHi, Thanks both for the compliments on the blog. Regarding drift, I have not noticed any, but I have not really been looking for it. One thing I have done is modify the accelerometer to by pass the low pass filter to fix a different issue. The modification is suggested and described in the comments here though not that I am not recommending that you do it as it may not be required for your application, as with anything on the web, do your own research to confirm it ! - http://www.sparkfun.com/products/9424
ReplyDeleteDuane.
Duane,
ReplyDeleteI hope you had a great holiday. I am looking at this project now in parallel with the lap timer project which has kind of gone off the boil whilst I try and work out a multi transponder apporach.
Did you get anywhere with version1? If possible could you forward it.
i am planning to see if I can use the y axis from the gyro to control the angle of the nose on an off road buggy aswell as the potential benefit of using the yaw control to help drivers develop corner speed.
Thanks
Graham
Hi,
DeleteI originally used a helicopter rate gyro in an RC Car, with these you can get the counter steer reaction in the steering servo without needing an Arduino involved. http://rcarduino.blogspot.com/2011/12/anti-yaw-control-part-1.html
The limitation is that oversteer is generally a power problem and the rate gyro on its own does nothing to address the power/throttle - only the steering.
The system would definitley make RWD buggies easier to drive - possibly at the cost of fun ?
A project I want to get back to is the 4WD M07 I built by joining a RWD chassis to a FWD Chassis, the car was way over powered with a lot of oversteer, but by using the yaw control on the RWD half the car should be very quick and very drivable.
I also have an idea to convert it to a sort of scale Group B Rally car with lots of turbo lag before a tsunami of boost kicks in.
For the lap timer my original has a different pinout to the build along version which slows me down so I plan to build a new one using the same published pinout and start working on some updates.
Duane
Duane,
DeleteSorry I meant version 1 of this project. As I use computer radios with variable end points etc I am keen to add a tranmitter learning function to the code, such that it can learn and remember the MIN/MAX limits. With the 40Kg servos I use you can do a lot of damage by trying to go past the mrchanical endstops of the system.
Makes sense for any additions to be based on the latest code.
Thanks
Graham
Hi,
DeleteAfter the challenge of getting the project to this point, adding indicators etc was less exciting and so this is the latest version that I have. If you were to add anything an indicator for each of 1) Measured rotation rate 2) Throttle Intervention and 3) Steering intervention would definitely help with fine tuning a car.
If you look at the readSettingsFromEEPROM and writeSettingsToEEPROM functions you will see that the code already has persistent calibration.
Duane B
Duane,
DeleteNo worries thanks for the reply. I cannot see whare there is a setup such that actual neutral, min and max are measured and stored, am I missing something??
Hardware should be here tomorrow so I can get this up and running for a test.
Hi,
DeleteYes your missing quite a bit. The sketch isn't too long, but it does a lot. There are two programming modes as well as the running mode. The first programming mode is accessed by pressing the program button for less than two seconds. This mode simply reads the throttle and steering intervention sensitivity pots so you can individually control how much the system will intervene in the throttle and steering channels.
To access the second full programming mode you hold the program button for more than two seconds. In this mode the Arduino will monitor the transmitter range and record these as the center, min and max end points, these end points are used in the running mode, the intervention will not exceed them.
Duane B
Can you explain how you did the "lost signal detection".
ReplyDeleteelse if(gMode == MODE_RUN)
Delete{
if((ulLastThrottleIn + 500) < ulMillis)
{
gMode = MODE_ERROR;
I think this is the code that effectively does the throttle lost signal check.
Every time a throttle update is received it updates ulLastThrottleIn.
So if 500ms have passed since the last update, go and go ERROR.
else if(gMode == MODE_ERROR)
{
servoThrottle.writeMicroseconds(unThrottleCenter);
Which centres the throttle channel.
Hope this helps
Yes thanks. When I use my RC control out of rang or at border, the signal is't away but genrates random servo/throttle reactions.
DeleteShouldn't this covert to for a fail safe routine?
Hi,
ReplyDeleteHowie314 is correct however as you have seen different models of receiver can perform differently at the limits of thier range. In your case the rate of bad signals to good signals increases towards the limits of the range. This is actually a good thing which you can use to set an indicator on the car to tell you that is getting towards its limit but crucially you still have control and do not need to enter an error mode where you no longer have full control. I often use this model with some of my own transmitters so will dig up an example in the next few days. Its a good idea to check what your radio does at the limit, I saw a post recently where a very cheap receiver carried on sending the last known good signal, this more or less guarantees a run away once you get out of range - here an Arduino could hel by monitoring for changes in signals, if none are detected the vehicle is past range and should be stopped. Duane B
Hi,
ReplyDeleteI wanted to let you know your Arduino project has been added to a list of 20 Arduino projects of 2012 published on Nudatech's blog ( http://www.nudatech.com/blog/20-arduino-projects-of-2012/ ).
Please let me know if there's any mistake in the short note I wrote about it and if the link I chose for it is the right one.
Obviously sharing the list on social networks, blogs and forums is also appreciated :-)
Regards
Hi,
ReplyDeleteThanks for including this in your list of 2012 projects. Did you have a look at this as well - http://rcarduino.blogspot.com/2012/08/the-must-build-arduino-project-illutron.html
I don't do much on social networks but thousands of people visit this blog each month.
Duane B
Hi is it possible to use your code with an adafruit 4WD motor shield? I don't get how to implement the code with the program 1 mode?
ReplyDeletecan you post a wiring diagram
ReplyDelete
ReplyDeleteThank you for taking the time to publish this information very useful! I've been looking for books of this nature for a way too long. I'm just glad that I found yours. Looking forward for your next post. Thanks :)
anti skid tapes supplier in india
I couldn't find a circuit diagram here, is that available please ?
ReplyDeleteThanks
John
nice share
ReplyDeleteThis comment has been removed by the author.
ReplyDeleteWow amazing post.
ReplyDeleteWe also provide every latest information on remote control cars from how to fix remote control car to how to make a remote control car easy
hi can u provide schematics how the parts are connected? i would like to build the samen.
ReplyDeleteThanks
Your blog post on RC Arduino yaw control is a fascinating read. It's evident that you have a deep understanding of this subject, and your ability to explain complex topics in a straightforward manner is commendable.
ReplyDeletepromocodehq
"I can't thank you enough for sharing this valuable information. Your blog has been a game-changer for me, and I look forward to every new post."
ReplyDeletehttps://savingcentstogether.com/promotions/asus-student-discount
"Your blog is more than just a source of information; it's a source of inspiration. It has motivated me to pursue my own passions and goals."
ReplyDeletehttps://justamazingdiscounts.com/brand/craigslist-pensacola/
Your detailed exploration of RCArduino Yaw Control - Part 2 is both informative and engaging. The precision in your explanations is as meticulous as one might appreciate when considering 'https://usepromos.com/how-much-does-platos-closet-pay-for-clothes/.' A technical journey that seamlessly blends expertise and curiosity
ReplyDeleteAppreciating the persistence you put into your blog and the detailed information you provide. Keep up the good work.
ReplyDeletechocolate box packaging manufacturer singapore
plastic cup manufacturer singapore
plastic injection moulding company singapore