The high and low signals that control servo motors must last for very precise periods of time. That’s because a servo motor measures how long the signal stays high, and uses that as an instruction for how fast, and in which direction, to turn its motor.
This timing diagram shows a servo signal that would make your Shield-Bot’s wheel turn full speed counterclockwise. There’s one big difference though: all the signals in this timing diagram last 100 times longer than they would if they were controlling a servo. This slows it down enough so that we can see what’s going on.
/* Robotics with the BOE Shield - ServoSlowMoCcw Send 1/100th speed servo signals for viewing with an LED. */ void setup() // Built in initialization block { pinMode(13, OUTPUT); // Set digital pin 13 -> output } void loop() // Main loop auto-repeats { digitalWrite(13, HIGH); // Pin 13 = 5 V, LED emits light delay(170); // ..for 0.17 seconds digitalWrite(13, LOW); // Pin 13 = 0 V, LED no light delay(1830); // ..for 1.83 seconds }
Alright, how about 1/10th speed instead of 1/100th speed?
Is the LED blinking 10 times faster now? Divide by 10 again for a full speed servo signal—we’ll have to round the numbers a bit:
Now you can see what the servo signal looks like with the indicator LED. The LED is flickering so fast, it’s just a glow. Since the high signal is 2 ms instead of 1.7 ms, it’ll be a little brighter than the actual servo control signal—the light is spending more time on. We could use this signal and programming technique to control a servo, but there’s an easier, more precise way. Let’s try it with LEDs first.
A better way to generate servo control signals is to include the Arduino Servo library in your sketch, one of the standard libraries of pre-written code bundled with the Arduino software.
We want to take a closer look at the Servo library.
attach()
writeMicroseconds()
detach()
Servos have to receive high-pulse control signals at regular intervals to keep turning. If the signal stops, so does the servo. Once your sketch uses the Servo library to set up the signal, it can move on to other code, like delays, checking sensors, etc. Meanwhile, the servo keeps turning because the Servo library keeps running in the background. It regularly interrupts the execution of other code to initiate those high pulses, doing it so quickly that it’s practically unnoticeable.
Using the Servo library to send servo control signals takes four steps:
#include <Servo.h> // Include servo library
Servo servoLeft; // Declare left servo
servoLeft.attach(13); // Attach left signal to pin 13
servoLeft.writeMicroseconds(1500); // 1.5 ms stay-still signal
Seconds, Milliseconds, Microseconds
A millisecond is a one-thousandth of a second, abbreviated ms.
A microsecond is a one-millionth of a second, abbreviated μs.
There are 1000 microseconds (μs) in 1 millisecond (ms).
There are 1,000,000 microseconds in 1 second (s).
For calibrating servos, your sketch will need to send signals with 1.5 ms pulses. Take a look at the timing diagram below. This stay-still signal’s high pulses last 1.5 ms. That’s halfway between the 1.7 ms full-speed-counterclockwise and 1.3 ms full-speed-clockwise pulses.
/* Robotics with the BOE Shield – LeftServoStayStill Generate signal to make the servo stay still for centering. */ #include <Servo.h> // Include servo library Servo servoLeft; // Declare left servo void setup() // Built in initialization block { servoLeft.attach(13); // Attach left signal to pin 13 servoLeft.writeMicroseconds(1500); // 1.5 ms stay still signal } void loop() // Main loop auto-repeats { // Empty, nothing needs repeating }
You’ll be using this code a lot, so it’s a good idea to practice declaring an instance of Servo, attaching the signal to a pin, and setting the pulse duration.
Servo servoRight; // Declare right servo
servoRight.attach(12); // Attach right signal to pin 12
servoRight.writeMicroseconds(1500); // 1.5 ms stay still signal
/* Robotics with the BOE Shield – BothServosStayStill Generate signals to make the servos stay still for centering. */ #include <Servo.h> // Include servo library Servo servoLeft; // Declare left servo signal Servo servoRight; // Declare right servo signal void setup() // Built in initialization block { servoLeft.attach(13); // Attach left signal to pin 13 servoRight.attach(12); // Attach left signal to pin 12 servoLeft.writeMicroseconds(1500); // 1.5 ms stay still sig, pin 13 servoRight.writeMicroseconds(1500); // 1.5 ms stay still sig, pin 12 } void loop() // Main loop auto-repeats { // Empty, nothing needs repeating }