Radio Controlled Robot - Arduino Based with XBee (Zigbee) Transceivers
Below is a video of the second version of a radio controlled robot. The intention was to build a robot capable of pulling a reel type lawn mower. Control of the robot is by using a handheld control box with commands sent to the robot by radio. The robot is driven by one 350W 24VDC gearmotor. The motor is linked through two gear reductions by size 40 chain sprockets to a drive wheel. The two drive wheels are on the same driven shaft.
Documentation for this robot follows. The first is a drawing of the electrical arrangement of the robot and control box.
C++ CODE
The transmitter and receiver Arduino microprocessor sketches (programming code) are below.
Robot Control Box Transmitter
/* Reads two potentiometers and sends via XBee to anothe XBee. One potentiometer is
* to set drive motor speed and direction. The other is to set desired position of
* a linear actuator which is used for steering. Data is sent with checksum
* to permit error check at receiver. Sends 8-bit value (0-255).
* Notes: 1. XBees must be programmed for 57600 baud. See Setup.
* 2. Set serial monitor to 57600 baud when debugging.
* Data transfer technique from
* https://henryforceblog.wordpress.com/2015/03/12/designing-a-communication-protocol-using-arduinos-serial-library/
*
*/
const uint8_t bufferSize = 4; // uint8_t is an unsigned 8 bit integer
uint8_t buffer[bufferSize]; // Array for data to be sent
int FB, LR;
int FBPin = A3; // pin = A3 potentiometer forward & back
int LRPin = A5; // pin = A5 potentiometer side to side
uint8_t i; // index within checksum function
int chksum = 0; // checksum put into buffer[3]
// Print out data for debugging. Comment out in loop if not wanted.
void debugData() {
Serial.print("Motor Speed: "); Serial.print(FB);
Serial.print(" Lin Act Wanted: "); Serial.print(LR);
Serial.println("");
}
void setup(){
// while(!Serial);
Serial.begin(57600);
// Header byte defined only once. It will not be changed.
buffer[0] = 0x7E; // 8 bit byte (0x7E=01111110)
// Declare pinModes for potentiometer inputs
pinMode(FBPin, INPUT); // Potentiometer to set forward speed
pinMode(LRPin, INPUT); // Potentiometer to set left-right position
delay(250);
}
void loop(){
//Read potentiometer values
int FB = analogRead(FBPin); // Returns digital 0 - 1023 from anlog input
int LR = analogRead(LRPin); // Returns digital 0 - 1023 from anlog input
// Digital poteniometer readings must be divided by 4 to make maximum 8 bits 0 - 255
/*buffer[1] = FB/4;
buffer[2] = LR/4;
buffer[3] = checksum(); */
// Bitshifting 2 places is faster than dividing by 4, but a little harder to understand.
// After shifting AND the result with 0xFF because the value is a 16 bit value
// int is a signed 16 bit value in Arduino 8 bit boards.
buffer[1] = (FB >> 2) & 0xFF; // 0xFF is 255 digital, binary 11111111
buffer[2] = (LR >> 2) & 0xFF;
buffer[3] = checksum();
// Send all bytes stored in the buffer[] array
Serial.write(buffer, bufferSize);
delay(100);
// debugData();
}
// Sum the buffer[] array bytes, except the last one which corresponds to the
// checksum value. After summing we need to AND the result to a byte value.
uint8_t checksum(){
uint8_t chksum = 0;
uint16_t sum = 0;
for(uint8_t i = 0; i < (bufferSize - 1); i++){
sum += buffer[i];
}
chksum = sum & 0xFF;
return chksum;
}
Robot Receiver
/*
From https://henryforceblog.wordpress.com/2015/03/12/designing-a-communication-protocol-using-arduinos-serial-library/
Receives two potentiometer readings and a checksum. One is used to control drive
motor speed and direction. Cytron 30A 5-30V Single Brushed DC Motor Driver
MD30C R2 used for motor. The other potentiometer reading sets the position
of the steering linear actuator. The linear actuator is Progressive
Automations model PA-14P-6-150-24VDC with potentiometer position indication.
The actuator is to move to the position where its potentiometer reading
matches the reading sent from the remote potentiometer.
Cytron 10A Motor Driver Shield MD10-R2 is used to power the linear actuator.
Looking at female end of cable toward linear actuator the pinout is:
Clip
|X|
__________________
| (POT) (-) (+) |
| (5V) (GND) ( ) |
|_________________|
The data string includes both pieces of data with checksum permit error checking.
Notes: 1. XBees must be programmed for 57600 baud.
2. Set serial monitor to 57600 baud when debugging.
Nomenclature - ADC = analog to digital converter
*/
const uint8_t header = 0x7E;
const uint8_t bufferSize = 4;
uint8_t buffer[bufferSize];
uint8_t readCounter;
uint8_t isHeader;
//Flag to restart counter when first header byte is found
uint8_t firstTimeHeader;
uint8_t MotorDir = 1; // Motor direction: 1 = forward, 0 = reverse
uint8_t MotorSpeed = 0; // 0 = stopped, 255 = full speed
int PotWanted = 512; // Error checked desired actuator position
uint8_t PotIn = 127; // Desired Actuator position, 0(all in) to 255(all out)
int PotReading = 512; // Variable for actual position of actuator, 0 - 1023
const int PotMiddle = 512; // Middle reading of linear actuator potentiometer
bool LinAcReady = false; // Linear actuator is or is not in desired position
int MotorDirPin = 9; // motor direction on Pin = 9
int MotorPin = 5; // motor speed as PWM on Pin = 5
int LinAcPin = 6; // linear actuator power enable on Pin = 6
int LinAcDirPin = 2; // linear actuator direction; in or out on Pin = 2
int PotPin = A5; // linear actuator potentiometer position on Pin = A5
// Used for timeouts upon loss of signal
unsigned long currentTime;
unsigned long timeOfLastGoodPacket = 0;
// General for Uno; analogWrite works on pins 3, 5, 6, 9, 10, and 11
// PWM with 0 being off and 255 being full on.
/******************************************************************************
Look for data connection loss. Compare the current time to time of last receipt
of good packet. If a second has passed, stop the motor.
******************************************************************************/
void timecheck() {
if (currentTime > (timeOfLastGoodPacket + 1000)) {
allStop();
}
else { }
}
/******************************************************************************
Set the speed of robot drive motor to zero
******************************************************************************/
void allStop() {
MotorSpeed = 0; // motor speed variable now defined when returned to loop
digitalWrite(MotorPin, LOW); // set Zero drive motor speed
digitalWrite(MotorDirPin, HIGH);
}
/******************************************************************************
Check Whethether Linear Actuator is in Desired Position
******************************************************************************/
void CheckLinAct() {
PotReading = analogRead(PotPin);
delay(1); // give ADC time to settle
PotReading = analogRead(PotPin);
// inside deadband at center
if((PotReading <= (PotWanted + 5)) && (PotReading >= (PotWanted - 5))) {
LinAcReady = true;
}
else {LinAcReady = false;}
}
/******************************************************************************
Move Linear Actuator to Desired Position
******************************************************************************/
void MoveLinAct() {
if(LinAcReady == true) {
digitalWrite(LinAcPin, LOW); // linear acutator is in position, disable its motor
}
else if(LinAcReady == false) {
if(PotReading > (PotWanted + 5)) { // > than deadband +5 more than wanted
digitalWrite(LinAcPin, HIGH); // linear acutator is not in position, run its motor
digitalWrite(LinAcDirPin, LOW); // actuator moving in
}
else if(PotReading <= (PotWanted - 5)) { // < deadband -5 less than wanted
digitalWrite(LinAcPin, HIGH);
digitalWrite(LinAcDirPin, HIGH); // actuator moving out
}
}
}
/* Use for debugging if needed
void debugData() {
Serial.print("Motor Speed: "); Serial.print(MotorSpeed);
Serial.print(" Motor Dir: "); Serial.print(MotorDir);
Serial.print(" Lin Act Wanted: "); Serial.print(PotWanted);
Serial.print(" Lin Act Reading: "); Serial.print(PotReading);
Serial.print(" Good Packet Time: "); Serial.print(timeOfLastGoodPacket);
Serial.print(" Current Time: "); Serial.print(currentTime);
Serial.println("");
} */
void setup() {
Serial.begin(57600); // opens serial port, sets data rate to 57600 bps
readCounter = 0;
isHeader = 0;
firstTimeHeader = 0;
pinMode(MotorPin, OUTPUT); // Motor speed pin as PWM, 0 (off) - 255 (full on)
pinMode(MotorDirPin, OUTPUT); // motor direction, forward or reverse
pinMode(LinAcPin, OUTPUT); // Linear actuator power on
pinMode(LinAcDirPin, OUTPUT); // linear actuator direction, in or out
pinMode(PotPin, INPUT); // Linear Actuator potentiometer actual position
// Make sure motor is stopped for safety
digitalWrite(MotorPin, LOW); // set Zero motor speed
digitalWrite(MotorDirPin, HIGH);
PotWanted = PotMiddle; // center linear actuator before doing anything else
CheckLinAct();
if(LinAcReady == false) { MoveLinAct(); }
delay(100);
}
void loop(){
currentTime = millis();
if (Serial.available() > 0) {
//read only one byte at a time
uint8_t c = Serial.read();
//Check if header is found
if(c == header){
/* Sometimes unformatted data wil be received. If so ignore it and restart
reading bytes. For the first time header is found restart readCounter indicating
that data is coming. It is possible the header appears again as a data byte. if so,
this conditional applies and readCounter is not restarted which would corrupt data.
*/
if(!firstTimeHeader){
isHeader = 1;
readCounter = 0;
firstTimeHeader = 1;
}
}
//store received byte, increase readCounter
buffer[readCounter] = c;
readCounter++;
//prior overflow, we have to restart readCounter
if(readCounter >= bufferSize){
readCounter = 0;
//if header was found
if(isHeader){
//get checksum value from buffer's last value, according to defined protocol
uint8_t checksumValue = buffer[3];
//perform checksum validation
if(verifyChecksum(checksumValue)){
if(buffer[1] <= 126) {
MotorDir = 0;
MotorSpeed = abs(127 - buffer[1]);
}
else {
MotorDir = 1;
MotorSpeed = abs(((buffer[1]-127) * 2) - 1);
}
PotIn = buffer[2];
PotWanted = PotIn * 4;
timeOfLastGoodPacket = currentTime;
analogWrite(MotorPin, MotorSpeed); // set motor speed
digitalWrite(MotorDirPin, MotorDir);
CheckLinAct();
MoveLinAct();
}
//restart header flag
isHeader = 0;
firstTimeHeader = 0;
delay(50);
}
}
}
timecheck(); // stop robot if radio communication is lost
}
/******************************************************************************
Error Checking using Check Sum Method
******************************************************************************/
// Sum all bytes in buffer[] array, except the one that corresponds to the original
// checksum. After summing AND with 0xFF to result in a byte.
uint8_t verifyChecksum(uint8_t originalResult){
uint8_t result = 0;
uint16_t sum = 0;
for(uint8_t i = 0; i < (bufferSize - 1); i++){
sum += buffer[i];
}
result = sum & 0xFF;
if(originalResult == result){
return 1;
}
else{
return 0;
}
}
The transmitter and receiver Arduino microprocessor sketches (programming code) are below.
Robot Control Box Transmitter
/* Reads two potentiometers and sends via XBee to anothe XBee. One potentiometer is
* to set drive motor speed and direction. The other is to set desired position of
* a linear actuator which is used for steering. Data is sent with checksum
* to permit error check at receiver. Sends 8-bit value (0-255).
* Notes: 1. XBees must be programmed for 57600 baud. See Setup.
* 2. Set serial monitor to 57600 baud when debugging.
* Data transfer technique from
* https://henryforceblog.wordpress.com/2015/03/12/designing-a-communication-protocol-using-arduinos-serial-library/
*
*/
const uint8_t bufferSize = 4; // uint8_t is an unsigned 8 bit integer
uint8_t buffer[bufferSize]; // Array for data to be sent
int FB, LR;
int FBPin = A3; // pin = A3 potentiometer forward & back
int LRPin = A5; // pin = A5 potentiometer side to side
uint8_t i; // index within checksum function
int chksum = 0; // checksum put into buffer[3]
// Print out data for debugging. Comment out in loop if not wanted.
void debugData() {
Serial.print("Motor Speed: "); Serial.print(FB);
Serial.print(" Lin Act Wanted: "); Serial.print(LR);
Serial.println("");
}
void setup(){
// while(!Serial);
Serial.begin(57600);
// Header byte defined only once. It will not be changed.
buffer[0] = 0x7E; // 8 bit byte (0x7E=01111110)
// Declare pinModes for potentiometer inputs
pinMode(FBPin, INPUT); // Potentiometer to set forward speed
pinMode(LRPin, INPUT); // Potentiometer to set left-right position
delay(250);
}
void loop(){
//Read potentiometer values
int FB = analogRead(FBPin); // Returns digital 0 - 1023 from anlog input
int LR = analogRead(LRPin); // Returns digital 0 - 1023 from anlog input
// Digital poteniometer readings must be divided by 4 to make maximum 8 bits 0 - 255
/*buffer[1] = FB/4;
buffer[2] = LR/4;
buffer[3] = checksum(); */
// Bitshifting 2 places is faster than dividing by 4, but a little harder to understand.
// After shifting AND the result with 0xFF because the value is a 16 bit value
// int is a signed 16 bit value in Arduino 8 bit boards.
buffer[1] = (FB >> 2) & 0xFF; // 0xFF is 255 digital, binary 11111111
buffer[2] = (LR >> 2) & 0xFF;
buffer[3] = checksum();
// Send all bytes stored in the buffer[] array
Serial.write(buffer, bufferSize);
delay(100);
// debugData();
}
// Sum the buffer[] array bytes, except the last one which corresponds to the
// checksum value. After summing we need to AND the result to a byte value.
uint8_t checksum(){
uint8_t chksum = 0;
uint16_t sum = 0;
for(uint8_t i = 0; i < (bufferSize - 1); i++){
sum += buffer[i];
}
chksum = sum & 0xFF;
return chksum;
}
Robot Receiver
/*
From https://henryforceblog.wordpress.com/2015/03/12/designing-a-communication-protocol-using-arduinos-serial-library/
Receives two potentiometer readings and a checksum. One is used to control drive
motor speed and direction. Cytron 30A 5-30V Single Brushed DC Motor Driver
MD30C R2 used for motor. The other potentiometer reading sets the position
of the steering linear actuator. The linear actuator is Progressive
Automations model PA-14P-6-150-24VDC with potentiometer position indication.
The actuator is to move to the position where its potentiometer reading
matches the reading sent from the remote potentiometer.
Cytron 10A Motor Driver Shield MD10-R2 is used to power the linear actuator.
Looking at female end of cable toward linear actuator the pinout is:
Clip
|X|
__________________
| (POT) (-) (+) |
| (5V) (GND) ( ) |
|_________________|
The data string includes both pieces of data with checksum permit error checking.
Notes: 1. XBees must be programmed for 57600 baud.
2. Set serial monitor to 57600 baud when debugging.
Nomenclature - ADC = analog to digital converter
*/
const uint8_t header = 0x7E;
const uint8_t bufferSize = 4;
uint8_t buffer[bufferSize];
uint8_t readCounter;
uint8_t isHeader;
//Flag to restart counter when first header byte is found
uint8_t firstTimeHeader;
uint8_t MotorDir = 1; // Motor direction: 1 = forward, 0 = reverse
uint8_t MotorSpeed = 0; // 0 = stopped, 255 = full speed
int PotWanted = 512; // Error checked desired actuator position
uint8_t PotIn = 127; // Desired Actuator position, 0(all in) to 255(all out)
int PotReading = 512; // Variable for actual position of actuator, 0 - 1023
const int PotMiddle = 512; // Middle reading of linear actuator potentiometer
bool LinAcReady = false; // Linear actuator is or is not in desired position
int MotorDirPin = 9; // motor direction on Pin = 9
int MotorPin = 5; // motor speed as PWM on Pin = 5
int LinAcPin = 6; // linear actuator power enable on Pin = 6
int LinAcDirPin = 2; // linear actuator direction; in or out on Pin = 2
int PotPin = A5; // linear actuator potentiometer position on Pin = A5
// Used for timeouts upon loss of signal
unsigned long currentTime;
unsigned long timeOfLastGoodPacket = 0;
// General for Uno; analogWrite works on pins 3, 5, 6, 9, 10, and 11
// PWM with 0 being off and 255 being full on.
/******************************************************************************
Look for data connection loss. Compare the current time to time of last receipt
of good packet. If a second has passed, stop the motor.
******************************************************************************/
void timecheck() {
if (currentTime > (timeOfLastGoodPacket + 1000)) {
allStop();
}
else { }
}
/******************************************************************************
Set the speed of robot drive motor to zero
******************************************************************************/
void allStop() {
MotorSpeed = 0; // motor speed variable now defined when returned to loop
digitalWrite(MotorPin, LOW); // set Zero drive motor speed
digitalWrite(MotorDirPin, HIGH);
}
/******************************************************************************
Check Whethether Linear Actuator is in Desired Position
******************************************************************************/
void CheckLinAct() {
PotReading = analogRead(PotPin);
delay(1); // give ADC time to settle
PotReading = analogRead(PotPin);
// inside deadband at center
if((PotReading <= (PotWanted + 5)) && (PotReading >= (PotWanted - 5))) {
LinAcReady = true;
}
else {LinAcReady = false;}
}
/******************************************************************************
Move Linear Actuator to Desired Position
******************************************************************************/
void MoveLinAct() {
if(LinAcReady == true) {
digitalWrite(LinAcPin, LOW); // linear acutator is in position, disable its motor
}
else if(LinAcReady == false) {
if(PotReading > (PotWanted + 5)) { // > than deadband +5 more than wanted
digitalWrite(LinAcPin, HIGH); // linear acutator is not in position, run its motor
digitalWrite(LinAcDirPin, LOW); // actuator moving in
}
else if(PotReading <= (PotWanted - 5)) { // < deadband -5 less than wanted
digitalWrite(LinAcPin, HIGH);
digitalWrite(LinAcDirPin, HIGH); // actuator moving out
}
}
}
/* Use for debugging if needed
void debugData() {
Serial.print("Motor Speed: "); Serial.print(MotorSpeed);
Serial.print(" Motor Dir: "); Serial.print(MotorDir);
Serial.print(" Lin Act Wanted: "); Serial.print(PotWanted);
Serial.print(" Lin Act Reading: "); Serial.print(PotReading);
Serial.print(" Good Packet Time: "); Serial.print(timeOfLastGoodPacket);
Serial.print(" Current Time: "); Serial.print(currentTime);
Serial.println("");
} */
void setup() {
Serial.begin(57600); // opens serial port, sets data rate to 57600 bps
readCounter = 0;
isHeader = 0;
firstTimeHeader = 0;
pinMode(MotorPin, OUTPUT); // Motor speed pin as PWM, 0 (off) - 255 (full on)
pinMode(MotorDirPin, OUTPUT); // motor direction, forward or reverse
pinMode(LinAcPin, OUTPUT); // Linear actuator power on
pinMode(LinAcDirPin, OUTPUT); // linear actuator direction, in or out
pinMode(PotPin, INPUT); // Linear Actuator potentiometer actual position
// Make sure motor is stopped for safety
digitalWrite(MotorPin, LOW); // set Zero motor speed
digitalWrite(MotorDirPin, HIGH);
PotWanted = PotMiddle; // center linear actuator before doing anything else
CheckLinAct();
if(LinAcReady == false) { MoveLinAct(); }
delay(100);
}
void loop(){
currentTime = millis();
if (Serial.available() > 0) {
//read only one byte at a time
uint8_t c = Serial.read();
//Check if header is found
if(c == header){
/* Sometimes unformatted data wil be received. If so ignore it and restart
reading bytes. For the first time header is found restart readCounter indicating
that data is coming. It is possible the header appears again as a data byte. if so,
this conditional applies and readCounter is not restarted which would corrupt data.
*/
if(!firstTimeHeader){
isHeader = 1;
readCounter = 0;
firstTimeHeader = 1;
}
}
//store received byte, increase readCounter
buffer[readCounter] = c;
readCounter++;
//prior overflow, we have to restart readCounter
if(readCounter >= bufferSize){
readCounter = 0;
//if header was found
if(isHeader){
//get checksum value from buffer's last value, according to defined protocol
uint8_t checksumValue = buffer[3];
//perform checksum validation
if(verifyChecksum(checksumValue)){
if(buffer[1] <= 126) {
MotorDir = 0;
MotorSpeed = abs(127 - buffer[1]);
}
else {
MotorDir = 1;
MotorSpeed = abs(((buffer[1]-127) * 2) - 1);
}
PotIn = buffer[2];
PotWanted = PotIn * 4;
timeOfLastGoodPacket = currentTime;
analogWrite(MotorPin, MotorSpeed); // set motor speed
digitalWrite(MotorDirPin, MotorDir);
CheckLinAct();
MoveLinAct();
}
//restart header flag
isHeader = 0;
firstTimeHeader = 0;
delay(50);
}
}
}
timecheck(); // stop robot if radio communication is lost
}
/******************************************************************************
Error Checking using Check Sum Method
******************************************************************************/
// Sum all bytes in buffer[] array, except the one that corresponds to the original
// checksum. After summing AND with 0xFF to result in a byte.
uint8_t verifyChecksum(uint8_t originalResult){
uint8_t result = 0;
uint16_t sum = 0;
for(uint8_t i = 0; i < (bufferSize - 1); i++){
sum += buffer[i];
}
result = sum & 0xFF;
if(originalResult == result){
return 1;
}
else{
return 0;
}
}
Assessment of Robot
The robot behaved perfectly in response to the controls. The programming code listed above is considered the final product and does not require any modifications. Unfortunately, the second mechanical design is not appropriate for pulling a reel type lawn mower.
1st Issue:
The weight of the robot (which is mostly the batteries) is not over the drive wheels. As a result, the wheels tend to slip in the grass.
2nd Issue:
The linear actuator used for steering is slow when rotating the steering wheels. This actuator moves about one inch per second at 24VDC. The total actuator travel to steer from side to side is about six inches. As a result the steering seems slow to respond to the control.
Coming Changes
The third version of the robot will be modified as follows:
Change 1:
Batteries need to be relocated over the drive wheel.
Change 2:
A faster linear actuator is desired to make the steering quicker.