Pololu Zumo Shield Arduino Library
ZumoMotors.cpp
1 #include "ZumoMotors.h"
2 
3 #define PWM_L 10
4 #define PWM_R 9
5 #define DIR_L 8
6 #define DIR_R 7
7 
8 #if defined(__AVR_ATmega168__) || defined(__AVR_ATmega328P__) || defined (__AVR_ATmega32U4__)
9  #define USE_20KHZ_PWM
10 #endif
11 
12 static boolean flipLeft = false;
13 static boolean flipRight = false;
14 
15 // constructor (doesn't do anything)
16 ZumoMotors::ZumoMotors()
17 {
18 }
19 
20 // initialize timer1 to generate the proper PWM outputs to the motor drivers
21 void ZumoMotors::init2()
22 {
23  pinMode(PWM_L, OUTPUT);
24  pinMode(PWM_R, OUTPUT);
25  pinMode(DIR_L, OUTPUT);
26  pinMode(DIR_R, OUTPUT);
27 
28 #ifdef USE_20KHZ_PWM
29  // Timer 1 configuration
30  // prescaler: clockI/O / 1
31  // outputs enabled
32  // phase-correct PWM
33  // top of 400
34  //
35  // PWM frequency calculation
36  // 16MHz / 1 (prescaler) / 2 (phase-correct) / 400 (top) = 20kHz
37  TCCR1A = 0b10100000;
38  TCCR1B = 0b00010001;
39  ICR1 = 400;
40 #endif
41 }
42 
43 // enable/disable flipping of left motor
44 void ZumoMotors::flipLeftMotor(boolean flip)
45 {
46  flipLeft = flip;
47 }
48 
49 // enable/disable flipping of right motor
50 void ZumoMotors::flipRightMotor(boolean flip)
51 {
52  flipRight = flip;
53 }
54 
55 // set speed for left motor; speed is a number between -400 and 400
56 void ZumoMotors::setLeftSpeed(int speed)
57 {
58  init(); // initialize if necessary
59 
60  boolean reverse = 0;
61 
62  if (speed < 0)
63  {
64  speed = -speed; // make speed a positive quantity
65  reverse = 1; // preserve the direction
66  }
67  if (speed > 400) // Max
68  speed = 400;
69 
70 #ifdef USE_20KHZ_PWM
71  OCR1B = speed;
72 #else
73  analogWrite(PWM_L, speed * 51 / 80); // default to using analogWrite, mapping 400 to 255
74 #endif
75 
76  if (reverse ^ flipLeft) // flip if speed was negative or flipLeft setting is active, but not both
77  digitalWrite(DIR_L, HIGH);
78  else
79  digitalWrite(DIR_L, LOW);
80 }
81 
82 // set speed for right motor; speed is a number between -400 and 400
83 void ZumoMotors::setRightSpeed(int speed)
84 {
85  init(); // initialize if necessary
86 
87  boolean reverse = 0;
88 
89  if (speed < 0)
90  {
91  speed = -speed; // Make speed a positive quantity
92  reverse = 1; // Preserve the direction
93  }
94  if (speed > 400) // Max PWM dutycycle
95  speed = 400;
96 
97 #ifdef USE_20KHZ_PWM
98  OCR1A = speed;
99 #else
100  analogWrite(PWM_R, speed * 51 / 80); // default to using analogWrite, mapping 400 to 255
101 #endif
102 
103  if (reverse ^ flipRight) // flip if speed was negative or flipRight setting is active, but not both
104  digitalWrite(DIR_R, HIGH);
105  else
106  digitalWrite(DIR_R, LOW);
107 }
108 
109 // set speed for both motors
110 void ZumoMotors::setSpeeds(int leftSpeed, int rightSpeed)
111 {
112  setLeftSpeed(leftSpeed);
113  setRightSpeed(rightSpeed);
114 }
ZumoMotors.h