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