-
Notifications
You must be signed in to change notification settings - Fork 1
/
Copy pathZumoShield.h
263 lines (217 loc) · 6.94 KB
/
ZumoShield.h
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
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
#include <ZumoBuzzer.h>
#include <ZumoMotors.h>
#include <Pushbutton.h>
#include <QTRSensors.h>
#include <ZumoReflectanceSensorArray.h>
#include <avr/pgmspace.h>
#include <LSM303.h>
#include <L3G.h>
#include <RunningAverage.h>
#include <Accelerometer.h>
extern ZumoMotors motors;
template <typename T> float heading(LSM303::vector<T> v, LSM303 *compass)
{
float x_scaled = 2.0*(float)(v.x - compass->m_min.x) / (compass->m_max.x - compass->m_min.x) - 1.0;
float y_scaled = 2.0*(float)(v.y - compass->m_min.y) / (compass->m_max.y - compass->m_min.y) - 1.0;
float angle = atan2(y_scaled, x_scaled)*180 / M_PI;
if (angle < 0)
angle += 360;
return angle;
}
#define CRB_REG_M_2_5GAUSS 0x60 // CRB_REG_M value for magnetometer +/-2.5 gauss full scale
#define CRA_REG_M_220HZ 0x1C // CRA_REG_M value for magnetometer 220 Hz update rate
#define SPEED 200
#define CALIBRATION_SAMPLES 70
class ZumoCompass : public LSM303
{
public:
ZumoCompass() {};
void begin() {
Wire.begin();
// Initiate LSM303
init();
// Enables accelerometer and magnetometer
enableDefault();
writeReg(LSM303::CRB_REG_M, CRB_REG_M_2_5GAUSS); // +/- 2.5 gauss sensitivity to hopefully avoid overflow problems
writeReg(LSM303::CRA_REG_M, CRA_REG_M_220HZ); // 220 Hz compass update rate
// Set calibrated values to compass.m_max and compass.m_min
m_max.x = 4156;
m_max.y = -838;
m_min.x = 2203;
m_min.y = -3406;
};
void setCalibration(int m_max_x, int m_max_y, int m_min_x, int m_min_y) {
m_max.x = m_max_x;
m_max.y = m_max_y;
m_min.x = m_min_x;
m_min.y = m_min_y;
}
void doCalibration(void) {
LSM303::vector<int16_t> running_min = {32767, 32767, 32767}, running_max = {-32767, -32767, -32767};
unsigned char index;
motors.setLeftSpeed(SPEED);
motors.setRightSpeed(-SPEED);
for(index = 0; index < CALIBRATION_SAMPLES; index ++) {
// Take a reading of the magnetic vector and store it in compass.m
read();
running_min.x = min(running_min.x, m.x);
running_min.y = min(running_min.y, m.y);
running_max.x = max(running_max.x, m.x);
running_max.y = max(running_max.y, m.y);
delay(50);
}
motors.setLeftSpeed(0);
motors.setRightSpeed(0);
setCalibration(running_min.x, running_min.y, running_max.x, running_max.y);
}
float averageHeading() {
LSM303::vector<int32_t> avg = {0, 0, 0};
for(int i = 0; i < 10; i ++)
{
read();
avg.x += m.x;
avg.y += m.y;
}
avg.x /= 10.0;
avg.y /= 10.0;
// avg is the average measure of the magnetic vector.
return ::heading(avg, (LSM303 *)this);
}
};
class ZumoGyro : public L3G
{
public:
ZumoGyro(void){};
/* turnAngle is a 32-bit unsigned integer representing the amount
the robot has turned since the last time turnSensorReset was
called. This is computed solely using the Z axis of the gyro, so
it could be inaccurate if the robot is rotated about the X or Y
axes.
Our convention is that a value of 0x20000000 represents a 45
degree counter-clockwise rotation. This means that a uint32_t
can represent any angle between 0 degrees and 360 degrees. If
you cast it to a signed 32-bit integer by writing
(int32_t)turnAngle, that integer can represent any angle between
-180 degrees and 180 degrees. */
uint32_t turnAngle = 0;
int32_t turnAngleDegree = 0;
// turnRate is the current angular rate of the gyro, in units of
// 0.07 degrees per second.
int16_t turnRate;
// This is the average reading obtained from the gyro's Z axis
// during calibration.
int16_t gyroOffset;
// This variable helps us keep track of how much time has passed
// between readings of the gyro.
uint16_t gyroLastUpdate = 0;
// This constant represents a turn of 45 degrees.
const int32_t turnAngle45 = 0x20000000;
// This constant represents a turn of 90 degrees.
const int32_t turnAngle90 = turnAngle45 * 2;
// This constant represents a turn of approximately 1 degree.
const int32_t turnAngle1 = (turnAngle45 + 22) / 45;
// This should be called to set the starting point for measuring
// a turn. After calling this, turnAngle will be 0.
void turnSensorReset() {
gyroLastUpdate = micros();
turnAngle = 0;
turnAngleDegree = 0;
}
// Read the gyro and update the angle. This should be called as
// frequently as possible while using the gyro to do turns.
void turnSensorUpdate() {
// Read the measurements from the gyro.
read();
turnRate = g.z - gyroOffset;
// Figure out how much time has passed since the last update (dt)
uint16_t m = micros();
uint16_t dt = m - gyroLastUpdate;
gyroLastUpdate = m;
// Multiply dt by turnRate in order to get an estimation of how
// much the robot has turned since the last update.
// (angular change = angular velocity * time)
int32_t d = (int32_t)turnRate * dt;
// The units of d are gyro digits times microseconds. We need
// to convert those to the units of turnAngle, where 2^29 units
// represents 45 degrees. The conversion from gyro digits to
// degrees per second (dps) is determined by the sensitivity of
// the gyro: 0.07 degrees per second per digit.
//
// (0.07 dps/digit) * (1/1000000 s/us) * (2^29/45 unit/degree)
// = 14680064/17578125 unit/(digit*us)
turnAngle += (int64_t)d * 14680064 / 17578125;
turnAngleDegree = ((int32_t)turnAngle / turnAngle1);
}
void turnSensorSetup() {
Wire.begin();
init();
// 800 Hz output data rate,
// low-pass filter cutoff 100 Hz
writeReg(L3G::CTRL1, 0b11111111);
// 2000 dps full scale
writeReg(L3G::CTRL4, 0b00100000);
// High-pass filter disabled
writeReg(L3G::CTRL5, 0b00000000);
// Delay to give the user time to remove their finger.
delay(500);
// Calibrate the gyro.
int32_t total = 0;
for (uint16_t i = 0; i < 1024; i++)
{
// Wait for new data to be available, then read it.
while(!readReg(L3G::STATUS_REG) & 0x08);
read();
// Add the Z axis reading to the total.
total += g.z;
}
gyroOffset = total / 1024;
// Display the angle (in degrees from -180 to 180) until the
// user presses A.
turnSensorReset();
};
};
class ZumoBuzzer2 : public ZumoBuzzer
{
public:
ZumoBuzzer2(){};
void playOn(void) {play(">g32>>c32");};
void playStart(void) {playNote(NOTE_G(4), 500, 15);}
void playNum(int cnt) {
for (int i = 0; i < cnt; i++){
delay(1000);
playNote(NOTE_G(3), 50, 12);
}
};
};
class ZumoLED
{
public:
ZumoLED(){pinMode(13, OUTPUT);};
void on(){digitalWrite(13, HIGH);};
void off(){digitalWrite(13, LOW);};
void set(int i){
digitalWrite(13, (i == 1)? HIGH : LOW);
};
};
class ZumoReflectanceSensorArray2 : public ZumoReflectanceSensorArray {
public:
unsigned int values[6];
ZumoReflectanceSensorArray2() : ZumoReflectanceSensorArray(QTR_NO_EMITTER_PIN){
};
void update(void){
read(values);
}
unsigned int value(int i){
if((i <= 6) && (i > 0)) {
return values[i-1];
}
return 0;
}
};
ZumoReflectanceSensorArray2 reflectances;
Pushbutton button(ZUMO_BUTTON);
ZumoLED led;
ZumoBuzzer2 buzzer;
ZumoCompass compass;
ZumoGyro gyro;
ZumoMotors motors;