More Precise BOE Shield Maneuvers with Encoders
More Precise Maneuvers with Encoders
As mentioned earlier, the Arlo has encoders that track distance in 144th increments of a full wheel rotation. These increments are commonly called “counts”, and the Arlo’s encoders send 144 counts per wheel revolution. The Arlo’s encoders are quadrature, meaning that the two encoder sensors are offset by ¼ of a count. The most important feature of quadrature encoding is that DHB-10 can determine which direction a wheel is turning by monitoring the pattern of low-high-low transitions for both sensors, the. For a given wheel, 144 counts would mean a full forward rotation, and -144 counts would mean a full backward rotation.
The Arlo’s DHB-10 motor controller has a built-in control system that uses the encoder outputs to control motor speed and distance as well as monitor motor position. The ArloRobot library has functions your sketch can call to both control speed and distance traveled, as well as poll current speed and distance.
NOTE: For more info on ArloRobot functions for Arduino, see the ArloRobot API (coming soon).
IMPORTANT: Make sure your sketch gives each maneuver enough time to finish before issuing a new distance command.
Distance Control
This example sketch uses the ArloRobot writeCounts function to tell the Arlo’s DHB-10 controller to make the Arlo travel certain numbers of encoder ticks, and the readCountsLeft and readCountsRight functions to check the actual distances traveled between each maneuver.
- Set power: MAIN (on), MOTORS (off), BOE Shield (position-2)
- Upload Arlo-Distance-Maneuvers.ino.
- Don’t worry about the communication error message because Motors power is off.
- Turn all power off, unplug programming cable, and take to your Arlo navigation area.
- Turn MAIN and MOTORS power on.
- Set the BOE Shield power switch to 2.
- Verify that the Arlo goes forward, turns left, then right, then left, then backs up to near where it started.
/*
Arlo-Distance-Maneuvers
Examples that use serial communication to make the arlo travel in certain
distances.
*/
#include <ArloRobot.h> // Include Arlo library
#include <SoftwareSerial.h> // Include SoftwareSerial library
// Arlo and serial objects required
ArloRobot Arlo; // Arlo object
SoftwareSerial ArloSerial(12, 13); // Serial in I/O 12, out I/O 13
int countsLeft, countsRight; // Encoder counting variables
void setup() // Setup function
{
tone(4, 3000, 2000); // Piezospeaker beep
Serial.begin(9600); // Start terminal serial port
Serial.println("Program running..."); // Display starting message
ArloSerial.begin(19200); // Start DHB-10 serial com
Arlo.begin(ArloSerial); // Pass to Arlo object
Arlo.clearCounts(); // Clear encoder counts
Arlo.writeCounts(144, 144); // Go forward 144 counts
delay(3000); // Wait three seconds
displayDistances(); // Display encoder counts
Arlo.writeCounts(-72, 72); // Turn left 72 counts
delay(2000); // Wait two seconds
displayDistances(); // Display encoder counts
Arlo.writeCounts(72, -72); // Turn right 72 counts
delay(2000); // Wait 2 seconds
displayDistances(); // Display encoder counts
Arlo.writeCounts(-144, -144); // Back up 144 counts
delay(3000); // Wait three seconds
displayDistances(); // Display encoder counts
}
void loop() {} // Nothing for main loop
void displayDistances()
{
countsLeft = Arlo.readCountsLeft(); // Get left & right encoder counts
countsRight = Arlo.readCountsRight();
Serial.print("countsLeft = "); // Display encoder measurements
Serial.print(countsLeft, DEC);
Serial.print(", countsRight = ");
Serial.println(countsRight, DEC);
}
Serial Speed Control
If your robot is using sensors to navigate, maybe you just want your sketch to make the Arlo go forward until it finds an obstacle. Instead of specifying a particular distance and setting aside a certain amount of time, your sketch can set each wheel speed and go until the sensors have detected a condition your sketch is looking for.
Speed control is very similar to distance control. The main difference is that the next sketch uses the ArloRobot object’s writeSpeeds function instead of writeCounts. The writeSpeeds function sets the left and right wheel speeds in terms of counts per second.
This next example sketch just goes forward at 144 counts per second for 3 seconds. Then, it turns left at 72 counts per second for 2 seconds. After that, it retraces its steps by turning right at 72 counts per second for 2 seconds, and then backing up at 144 counts per second for 3 seconds.
- Set power like this: MAIN (on), MOTORS (off), BOE Shield (position-2)
- Upload Serial Speed Maneuvers.ino.
- Disregard the communication error message.
- Turn all power off, unplug programming cable, and take to your Arlo navigation area.
- Turn MAIN and MOTORS power on.
- Set the BOE Shield power switch to 2.
- Verify that the Arlo goes forward, and then backwards.
- Try changing the left = 200 : right = 200 to left = 150 : right = 50.
- Change the left = -200 : right = -200 to left = -150 : right = -50.
/*
Arlo-Speed-Maneuvers
Examples that use ArloRobot library to make the arlo travel in certain
speeds for certain amounts of time.
*/
#include <ArloRobot.h> // Include Arlo library
#include <SoftwareSerial.h> // Include SoftwareSerial library
// Arlo and serial objects required
ArloRobot Arlo; // Arlo object
SoftwareSerial ArloSerial(12, 13); // Serial in I/O 12, out I/O 13
int countsLeft, countsRight; // Encoder counting variables
void setup() // Setup function
{
tone(4, 3000, 2000); // Piezospeaker beep
Serial.begin(9600); // Start terminal serial port
Serial.println("Sketch running..."); // Display starting message
ArloSerial.begin(19200); // Start DHB-10 serial com
Arlo.begin(ArloSerial); // Pass to Arlo object
Arlo.clearCounts(); // Clear encoder counts
Arlo.writeSpeeds(144, 144); // Go forward 144 counts/sec
delay(3000); // for three seconds
Arlo.writeSpeeds(0, 0); // Stop
delay(1000); // for one second
displayDistances(); // Display encoder counts
Arlo.writeSpeeds(-72, 72); // Rotate seft 72 counts/sec
delay(2000); // for two seconds
Arlo.writeSpeeds(0, 0); // Stop
delay(1000); // ...for one second
displayDistances(); // Display encoder counts
Arlo.writeSpeeds(72, -72); // Rotate right counts/sec
delay(2000); // for two seconds
Arlo.writeSpeeds(0, 0); // Stop
delay(1000); // for one second
displayDistances(); // Display encoder counts
Arlo.writeSpeeds(-144, -144); // Go backward 144 counts/sec
delay(3000); // for three seconds
Arlo.writeSpeeds(0, 0); // Stop
delay(1000); // for one second
displayDistances(); // Display encoder counts
}
void loop() {} // Nothing for main loop
void displayDistances()
{
countsLeft = Arlo.readCountsLeft(); // Get left & right encoder counts
countsRight = Arlo.readCountsRight();
Serial.print("countsLeft = "); // Display encoder measurements
Serial.print(countsLeft, DEC);
Serial.print(", countsRight = ");
Serial.println(countsRight, DEC);
}