This is the latest (main) BeagleBoard documentation. If you are looking for stable releases, use the drop-down menu on the bottom-left and select the desired version.

Motors

One of the many fun things about embedded computers is that you can move physical things with motors. But there are so many different kinds of motors (servo, stepper, DC), so how do you select the right one?

The type of motor you use depends on the type of motion you want:

  • R/C or hobby servo motor

    Can be quickly positioned at various absolute angles, but some don’t spin. In fact, many can turn only about 180{deg}.

  • Stepper motor

    Spins and can also rotate in precise relative angles, such as turning 45°. Stepper motors come in two types: bipolar (which has four wires) and unipolar (which has five or six wires).

  • DC motor

    Spins either clockwise or counter-clockwise and can have the greatest speed of the three. But a DC motor can’t easily be made to turn to a given angle.

When you know which type of motor to use, interfacing is easy. This chapter shows how to interface with each of these motors.

Note

Motors come in many sizes and types. This chapter presents some of the more popular types and shows how they can interface easily to the Bone. If you need to turn on and off a 120 V motor, consider using something like the PowerSwitch presented in Toggling a High-Voltage External Device.

Note

The Bone has built-in 3.3 V and 5 V supplies, which can supply enough current to drive some small motors. Many motors, however, draw enough current that an external power supply is needed. Therefore, an external 5 V power supply is listed as optional in many of the recipes.

Note

All the examples in the book assume you have cloned the Cookbook repository on git.beagleboard.org. Go here Cloning the Cookbook Repository for instructions.

Controlling a Servo Motor

Problem

You want to use BeagleBone to control the absolute position of a servo motor.

Solution

We’ll use the pulse width modulation (PWM) hardware of the Bone to control a servo motor.

To make the recipe, you will need:

  • Servo motor.

  • Breadboard and jumper wires.

  • 1 kΩ resistor (optional)

  • 5 V power supply (optional)

The 1 kΩ resistor isn’t required, but it provides some protection to the general-purpose input/output (GPIO) pin in case the servo fails and draws a large current.

Wire up your servo, as shown in Driving a servo motor with the 3.3 V power supply.

Note

There is no standard for how servo motor wires are colored. One of my servos is wired like Driving a servo motor with the 3.3 V power supply red is 3.3 V, black is ground, and yellow is the control line. I have another servo that has red as 3.3 V and ground is brown, with the control line being orange. Generally, though, the 3.3 V is in the middle. Check the datasheet for your servo before wiring.

Servo Motor

Fig. 319 Driving a servo motor with the 3.3 V power supply

The code for controlling the servo motor is in servoMotor.py, shown in Code for driving a servo motor (servoMotor.py). You need to configure the pin for PWM.

bone$ cd ~/beaglebone-cookbook-code/04motors
bone$ config-pin P9_16 pwm
bone$ ./servoMotor.py
Listing 30 Code for driving a servo motor (servoMotor.py)
 1#!/usr/bin/env python
 2# ////////////////////////////////////////
 3# //	servoMotor.py
 4# //	Drive a simple servo motor back and forth on P9_16 pin
 5# //	Wiring:
 6# //	Setup:  config-pin P9_16 pwm
 7# //	See:
 8# ////////////////////////////////////////
 9import time
10import signal
11import sys
12
13pwmPeriod = '20000000'    # Period in ns, (20 ms)
14pwm =     '1' # pwm to use
15channel = 'b' # channel to use
16PWMPATH='/dev/bone/pwm/'+pwm+'/'+channel
17low  = 0.8 # Smallest angle (in ms)
18hi   = 2.4 # Largest angle (in ms)
19ms   = 250 # How often to change position, in ms
20pos  = 1.5 # Current position, about middle ms)
21step = 0.1 # Step size to next position
22
23def signal_handler(sig, frame):
24    print('Got SIGINT, turning motor off')
25    f = open(PWMPATH+'/enable', 'w')
26    f.write('0')
27    f.close()
28    sys.exit(0)
29signal.signal(signal.SIGINT, signal_handler)
30print('Hit ^C to stop')
31
32f = open(PWMPATH+'/period', 'w')
33f.write(pwmPeriod)
34f.close()
35f = open(PWMPATH+'/enable', 'w')
36f.write('1')
37f.close()
38
39f = open(PWMPATH+'/duty_cycle', 'w')
40while True:
41    pos += step    # Take a step
42    if(pos > hi or pos < low):
43        step *= -1
44    duty_cycle = str(round(pos*1000000))    # Convert ms to ns
45    # print('pos = ' + str(pos) + ' duty_cycle = ' + duty_cycle)
46    f.seek(0)
47    f.write(duty_cycle)
48    time.sleep(ms/1000)
49
50# | Pin   | pwm | channel
51# | P9_31 | 0   | a
52# | P9_29 | 0   | b
53# | P9_14 | 1   | a
54# | P9_16 | 1   | b
55# | P8_19 | 2   | a
56# | P8_13 | 2   | b

servoMotor.py

Running the code causes the motor to move back and forth, progressing to successive positions between the two extremes. You will need to press ^C (Ctrl-C) to stop the script.

Controlling a Servo with an Rotary Encoder

Problem

You have a rotary encoder from Reading a rotary encoder (rotaryEncoder.js) that you want to control a servo motor.

Solution

Combine the code from Reading a rotary encoder (rotaryEncoder.js) and Controlling a Servo Motor.

bone$ config-pin P9_16 pwm
bone$ config-pin P8_11 eqep
bone$ config-pin P8_12 eqep
bone$ ./servoEncoder.py
Listing 32 Code for driving a servo motor with a rotary encorder(servoEncoder.py)
 1#!/usr/bin/env python
 2# ////////////////////////////////////////
 3# //	servoEncoder.py
 4# //	Drive a simple servo motor using rotary encoder viq eQEP 
 5# //	Wiring: Servo on P9_16, rotary encoder on P8_11 and P8_12
 6# //	Setup:  config-pin P9_16 pwm
 7# //			config-pin P8_11 eqep
 8# //			config-pin P8_12 eqep
 9# //	See:
10# ////////////////////////////////////////
11import time
12import signal
13import sys
14
15# Set up encoder
16eQEP = '2'
17COUNTERPATH = '/dev/bone/counter/counter'+eQEP+'/count0'
18maxCount = '180'
19
20ms = 100 	# Time between samples in ms
21
22# Set the eEQP maximum count
23fQEP = open(COUNTERPATH+'/ceiling', 'w')
24fQEP.write(maxCount)
25fQEP.close()
26
27# Enable
28fQEP = open(COUNTERPATH+'/enable', 'w')
29fQEP.write('1')
30fQEP.close()
31
32fQEP = open(COUNTERPATH+'/count', 'r')
33
34# Set up servo
35pwmPeriod = '20000000'    # Period in ns, (20 ms)
36pwm     = '1'  # pwm to use
37channel = 'b'  # channel to use
38PWMPATH='/dev/bone/pwm/'+pwm+'/'+channel
39low  = 0.6 # Smallest angle (in ms)
40hi   = 2.5 # Largest angle (in ms)
41ms   = 250 # How often to change position, in ms
42pos  = 1.5 # Current position, about middle ms)
43step = 0.1 # Step size to next position
44
45def signal_handler(sig, frame):
46    print('Got SIGINT, turning motor off')
47    f = open(PWMPATH+'/enable', 'w')
48    f.write('0')
49    f.close()
50    sys.exit(0)
51signal.signal(signal.SIGINT, signal_handler)
52
53f = open(PWMPATH+'/period', 'w')
54f.write(pwmPeriod)
55f.close()
56f = open(PWMPATH+'/duty_cycle', 'w')
57f.write(str(round(int(pwmPeriod)/2)))
58f.close()
59f = open(PWMPATH+'/enable', 'w')
60f.write('1')
61f.close()
62
63print('Hit ^C to stop')
64
65olddata = -1
66while True:
67	fQEP.seek(0)
68	data = fQEP.read()[:-1]
69	# Print only if data changes
70	if data != olddata:
71		olddata = data
72		# print("data = " + data)
73		# # map 0-180  to low-hi
74		duty_cycle = -1*int(data)*(hi-low)/180.0 + hi
75		duty_cycle = str(int(duty_cycle*1000000))	# Convert from ms to ns
76		# print('duty_cycle = ' + duty_cycle)
77		f = open(PWMPATH+'/duty_cycle', 'w')
78		f.write(duty_cycle)
79		f.close()
80	time.sleep(ms/1000)
81
82# Black OR Pocket
83# eQEP0:	P9.27 and P9.42 OR P1_33 and P2_34
84# eQEP1:	P9.33 and P9.35
85# eQEP2:	P8.11 and P8.12 OR P2_24 and P2_33
86
87# AI
88# eQEP1:	P8.33 and P8.35
89# eQEP2:	P8.11 and P8.12 or P9.19 and P9.41
90# eQEP3:	P8.24 and P8.25 or P9.27 and P9.42
91
92# | Pin   | pwm | channel
93# | P9_31 | 0   | a
94# | P9_29 | 0   | b
95# | P9_14 | 1   | a
96# | P9_16 | 1   | b
97# | P8_19 | 2   | a
98# | P8_13 | 2   | b

servoEncoder.py

Controlling the Speed of a DC Motor

Problem

You have a DC motor (or a solenoid) and want a simple way to control its speed, but not the direction.

Solution

It would be nice if you could just wire the DC motor to BeagleBone Black and have it work, but it won’t. Most motors require more current than the GPIO ports on the Bone can supply. Our solution is to use a transistor to control the current to the bone.

Here we configure the encoder to returns value between 0 and 180 inclusive. This value is then mapped to a value between min (0.6 ms) and max (2.5 ms). This number is converted from milliseconds and nanoseconds (time 1000000) and sent to the servo motor via the pwm.

Here’s what you will need:

  • 3 V to 5 V DC motor

  • Breadboard and jumper wires.

  • 1 kΩ resistor.

  • Transistor 2N3904.

  • Diode 1N4001.

  • Power supply for the motor (optional)

If you are using a larger motor (more current), you will need to use a larger transistor.

Wire your breadboard as shown in Wiring a DC motor to spin one direction.

DC Motor

Fig. 320 Wiring a DC motor to spin one direction

Use the code in Driving a DC motor in one direction (dcMotor.py) to run the motor.

Listing 33 Driving a DC motor in one direction (dcMotor.py)
 1#!/usr/bin/env python
 2# ////////////////////////////////////////
 3# //	dcMotor.js
 4# //	This is an example of driving a DC motor
 5# //	Wiring:
 6# //	Setup:  config-pin P9_16 pwm
 7# //	See:
 8# ////////////////////////////////////////
 9import time
10import signal
11import sys
12
13def signal_handler(sig, frame):
14    print('Got SIGINT, turning motor off')
15    f = open(PWMPATH+'/enable', 'w')
16    f.write('0')
17    f.close()
18    sys.exit(0)
19signal.signal(signal.SIGINT, signal_handler)
20
21pwmPeriod = '1000000'    # Period in ns
22pwm     = '1'  # pwm to use
23channel = 'b'  # channel to use
24PWMPATH='/dev/bone/pwm/'+pwm+'/'+channel
25
26low = 0.05     # Slowest speed (duty cycle)
27hi  = 1        # Fastest (always on)
28ms = 100       # How often to change speed, in ms
29speed = 0.5    # Current speed
30step = 0.05    # Change in speed
31
32f = open(PWMPATH+'/duty_cycle', 'w')
33f.write('0')
34f.close()
35f = open(PWMPATH+'/period', 'w')
36f.write(pwmPeriod)
37f.close()
38f = open(PWMPATH+'/enable', 'w')
39f.write('1')
40f.close()
41
42f = open(PWMPATH+'/duty_cycle', 'w')
43while True:
44    speed += step
45    if(speed > hi or speed < low):
46        step *= -1
47    duty_cycle = str(round(speed*1000000))    # Convert ms to ns
48    f.seek(0)
49    f.write(duty_cycle)
50    time.sleep(ms/1000)

dcMotor.py

See Also

How do you change the direction of the motor? See Controlling the Speed and Direction of a DC Motor.

Controlling the Speed and Direction of a DC Motor

Problem

You would like your DC motor to go forward and backward.

Solution

Use an H-bridge to switch the terminals on the motor so that it will run both backward and forward. We’ll use the L293D a common, single-chip H-bridge.

Here’s what you will need:

  • 3 V to 5 V motor.

  • Breadboard and jumper wires.

  • L293D H-Bridge IC.

  • Power supply for the motor (optional)

Lay out your breadboard as shown in Driving a DC motor with an H-bridge. Ensure that the L293D is positioned correctly. There is a notch on one end that should be pointed up.

H-bridge Motor

Fig. 321 Driving a DC motor with an H-bridge

The code in Code for driving a DC motor with an H-bridge (h-bridgeMotor.js) (h-bridgeMotor.js) looks much like the code for driving the DC motor with a transistor (Driving a DC motor in one direction (dcMotor.js)). The additional code specifies which direction to spin the motor.

Listing 35 Code for driving a DC motor with an H-bridge (h-bridgeMotor.js)
 1#!/usr/bin/env node
 2
 3// This example uses an H-bridge to drive a DC motor in two directions
 4
 5var b = require('bonescript');
 6
 7var enable = 'P9_21';    // Pin to use for PWM speed control
 8    in1    = 'P9_15',
 9    in2    = 'P9_16',
10    step = 0.05,    // Change in speed
11    min  = 0.05,    // Min duty cycle
12    max  = 1.0,     // Max duty cycle
13    ms   = 100,     // Update time, in ms
14    speed = min;    // Current speed;
15
16b.pinMode(enable, b.ANALOG_OUTPUT, 6, 0, 0, doInterval);
17b.pinMode(in1, b.OUTPUT);
18b.pinMode(in2, b.OUTPUT);
19
20function doInterval(x) {
21    if(x.err) {
22        console.log('x.err = ' + x.err);
23        return;
24    }
25    timer = setInterval(sweep, ms);
26}
27
28clockwise();        // Start by going clockwise
29
30function sweep() {
31    speed += step;
32    if(speed > max || speed < min) {
33        step *= -1;
34        step>0 ? clockwise() : counterClockwise();
35    }
36    b.analogWrite(enable, speed);
37    console.log('speed = ' + speed);
38}
39
40function clockwise() {
41    b.digitalWrite(in1, b.HIGH);
42    b.digitalWrite(in2, b.LOW);
43}
44
45function counterClockwise() {
46    b.digitalWrite(in1, b.LOW);
47    b.digitalWrite(in2, b.HIGH);
48}
49
50process.on('SIGINT', function() {
51    console.log('Got SIGINT, turning motor off');
52    clearInterval(timer);         // Stop the timer
53    b.analogWrite(enable, 0);     // Turn motor off
54});

h-bridgeMotor.js

Driving a Bipolar Stepper Motor

Problem

You want to drive a stepper motor that has four wires.

Solution

Use an L293D H-bridge. The bipolar stepper motor requires us to reverse the coils, so we need to use an H-bridge.

Here’s what you will need:

  • Breadboard and jumper wires.

  • 3 V to 5 V bipolar stepper motor.

  • L293D H-Bridge IC.

Wire as shown in Bipolar stepper motor wiring.

Bipolar Stepper Motor

Fig. 322 Bipolar stepper motor wiring

Use the code in Driving a bipolar stepper motor (bipolarStepperMotor.py) to drive the motor.

Listing 36 Driving a bipolar stepper motor (bipolarStepperMotor.py)
 1#!/usr/bin/env python
 2import time
 3import os
 4import signal
 5import sys
 6
 7# Motor is attached here
 8# controller = ["P9_11", "P9_13", "P9_15", "P9_17"]; 
 9# controller = ["30", "31", "48", "5"]
10# controller = ["P9_14", "P9_16", "P9_18", "P9_22"]; 
11controller = ["50", "51", "4", "2"]
12states = [[1,0,0,0], [0,1,0,0], [0,0,1,0], [0,0,0,1]]
13statesHiTorque = [[1,1,0,0], [0,1,1,0], [0,0,1,1], [1,0,0,1]]
14statesHalfStep = [[1,0,0,0], [1,1,0,0], [0,1,0,0], [0,1,1,0],
15                      [0,0,1,0], [0,0,1,1], [0,0,0,1], [1,0,0,1]]
16
17curState = 0    # Current state
18ms = 100        # Time between steps, in ms
19maxStep = 22    # Number of steps to turn before turning around
20minStep = 0     # minimum step to turn back around on
21
22CW  =  1       # Clockwise
23CCW = -1
24pos =  0       # current position and direction
25direction = CW
26GPIOPATH="/sys/class/gpio"
27
28def signal_handler(sig, frame):
29    print('Got SIGINT, turning motor off')
30    for i in range(len(controller)) :
31        f = open(GPIOPATH+"/gpio"+controller[i]+"/value", "w")
32        f.write('0')
33        f.close()
34    sys.exit(0)
35signal.signal(signal.SIGINT, signal_handler)
36print('Hit ^C to stop')
37
38def move():
39    global pos
40    global direction
41    global minStep
42    global maxStep
43    pos += direction
44    print("pos: " + str(pos))
45    # Switch directions if at end.
46    if (pos >= maxStep or pos <= minStep) :
47        direction *= -1
48    rotate(direction)
49
50# This is the general rotate
51def rotate(direction) :
52    global curState
53    global states
54	# print("rotate(%d)", direction);
55    # Rotate the state according to the direction of rotation
56    curState +=  direction
57    if(curState >= len(states)) :
58        curState = 0;
59    elif(curState<0) :
60        curState = len(states)-1
61    updateState(states[curState])
62
63# Write the current input state to the controller
64def updateState(state) :
65    global controller
66    print(state)
67    for i in range(len(controller)) :
68        f = open(GPIOPATH+"/gpio"+controller[i]+"/value", "w")
69        f.write(str(state[i]))
70        f.close()
71
72# Initialize motor control pins to be OUTPUTs
73for i in range(len(controller)) :
74    # Make sure pin is exported
75    if (not os.path.exists(GPIOPATH+"/gpio"+controller[i])):
76        f = open(GPIOPATH+"/export", "w")
77        f.write(pin)
78        f.close()
79    # Make it an output pin
80    f = open(GPIOPATH+"/gpio"+controller[i]+"/direction", "w")
81    f.write("out")
82    f.close()
83
84# Put the motor into a known state
85updateState(states[0])
86rotate(direction)
87
88# Rotate
89while True:
90    move()
91    time.sleep(ms/1000)

bipolarStepperMotor.py

When you run the code, the stepper motor will rotate back and forth.

Driving a Unipolar Stepper Motor

Problem

You want to drive a stepper motor that has five or six wires.

Solution

If your stepper motor has five or six wires, it’s a unipolar stepper and is wired differently than the bipolar. Here, we’ll use a ULN2003 Darlington Transistor Array IC to drive the motor.

Here’s what you will need:

  • Breadboard and jumper wires.

  • 3 V to 5 V unipolar stepper motor.

  • ULN2003 Darlington Transistor Array IC.

Wire, as shown in Unipolar stepper motor wiring.

Note

The IC in Unipolar stepper motor wiring is illustrated upside down from the way it is usually displayed.

That is, the notch for pin 1 is on the bottom. This made drawing the diagram much cleaner.

Also, notice the banded wire running the P9_7 (5 V) to the UL2003A. The stepper motor I’m using runs better at 5 V, so I’m using the Bone’s 5 V power supply. The signal coming from the GPIO pins is 3.3 V, but the U2003A will step them up to 5 V to drive the motor.

Unipolar Stepper Motor

Fig. 323 Unipolar stepper motor wiring

The code for driving the motor is in unipolarStepperMotor.js however, it is almost identical to the bipolar stepper code (Driving a bipolar stepper motor (bipolarStepperMotor.py)), so Changes to bipolar code to drive a unipolar stepper motor (unipolarStepperMotor.js.diff) shows only the lines that you need to change.

Listing 37 Changes to bipolar code to drive a unipolar stepper motor (unipolarStepperMotor.py.diff)
1# controller = ["P9_11", "P9_13", "P9_15", "P9_17"]
2controller = ["30", "31", "48", "5"]
3states = [[1,1,0,0], [0,1,1,0], [0,0,1,1], [1,0,0,1]]
4curState = 0   // Current state
5ms = 100       // Time between steps, in ms
6max = 200      // Number of steps to turn before turning around

unipolarStepperMotor.py.diff

Listing 38 Changes to bipolar code to drive a unipolar stepper motor (unipolarStepperMotor.js.diff)
1# var controller = ["P9_11", "P9_13", "P9_15", "P9_17"];
2controller = ["30", "31", "48", "5"]
3var states = [[1,1,0,0], [0,1,1,0], [0,0,1,1], [1,0,0,1]];
4var curState = 0;   // Current state
5var ms = 100,       // Time between steps, in ms
6    max = 200,      // Number of steps to turn before turning around

unipolarStepperMotor.js.diff

The code in this example makes the following changes:

  • The states are different. Here, we have two pins high at a time.

  • The time between steps (ms) is shorter, and the number of steps per direction (max) is bigger. The unipolar stepper I’m using has many more steps per rotation, so I need more steps to make it go around.