Zumo32U4 library
Zumo32U4Motors.cpp
1 // Copyright Pololu Corporation. For more information, see http://www.pololu.com/
2 
3 #include <Zumo32U4Motors.h>
4 #include <FastGPIO.h>
5 #include <avr/io.h>
6 
7 #define PWM_L 10
8 #define PWM_R 9
9 #define DIR_L 16
10 #define DIR_R 15
11 
12 static bool flipLeft = false;
13 static bool flipRight = false;
14 
15 // initialize timer1 to generate the proper PWM outputs to the motor drivers
16 void Zumo32U4Motors::init2()
17 {
18  FastGPIO::Pin<PWM_L>::setOutputLow();
19  FastGPIO::Pin<PWM_R>::setOutputLow();
20  FastGPIO::Pin<DIR_L>::setOutputLow();
21  FastGPIO::Pin<DIR_R>::setOutputLow();
22 
23  // Timer 1 configuration
24  // prescaler: clockI/O / 1
25  // outputs enabled
26  // phase-correct PWM
27  // top of 400
28  //
29  // PWM frequency calculation
30  // 16MHz / 1 (prescaler) / 2 (phase-correct) / 400 (top) = 20kHz
31  TCCR1A = 0b10100000;
32  TCCR1B = 0b00010001;
33  ICR1 = 400;
34  OCR1A = 0;
35  OCR1B = 0;
36 }
37 
38 // enable/disable flipping of left motor
40 {
41  flipLeft = flip;
42 }
43 
44 // enable/disable flipping of right motor
46 {
47  flipRight = flip;
48 }
49 
50 // set speed for left motor; speed is a number between -400 and 400
51 void Zumo32U4Motors::setLeftSpeed(int16_t speed)
52 {
53  init();
54 
55  bool reverse = 0;
56 
57  if (speed < 0)
58  {
59  speed = -speed; // Make speed a positive quantity.
60  reverse = 1; // Preserve the direction.
61  }
62  if (speed > 400) // Max PWM duty cycle.
63  {
64  speed = 400;
65  }
66 
67  OCR1B = speed;
68 
69  FastGPIO::Pin<DIR_L>::setOutput(reverse ^ flipLeft);
70 }
71 
72 // set speed for right motor; speed is a number between -400 and 400
73 void Zumo32U4Motors::setRightSpeed(int16_t speed)
74 {
75  init();
76 
77  bool reverse = 0;
78 
79  if (speed < 0)
80  {
81  speed = -speed; // Make speed a positive quantity.
82  reverse = 1; // Preserve the direction.
83  }
84  if (speed > 400) // Max PWM duty cycle.
85  {
86  speed = 400;
87  }
88 
89  OCR1A = speed;
90 
91  FastGPIO::Pin<DIR_R>::setOutput(reverse ^ flipRight);
92 }
93 
94 // set speed for both motors
95 void Zumo32U4Motors::setSpeeds(int16_t leftSpeed, int16_t rightSpeed)
96 {
97  setLeftSpeed(leftSpeed);
98  setRightSpeed(rightSpeed);
99 }
static void flipLeftMotor(bool flip)
Flips the direction of the left motor.
static void setRightSpeed(int16_t speed)
Sets the speed for the right motor.
static void flipRightMotor(bool flip)
Flips the direction of the right motor.
static void setLeftSpeed(int16_t speed)
Sets the speed for the left motor.
static void setSpeeds(int16_t leftSpeed, int16_t rightSpeed)
Sets the speeds for both motors.