-
Notifications
You must be signed in to change notification settings - Fork 17
/
LineFollower.ino
117 lines (96 loc) · 3.62 KB
/
LineFollower.ino
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
/*
* Demo line-following code for the Pololu Zumo Robot
*
* This code will follow a black line on a white background, using a
* PID-based algorithm. It works decently on courses with smooth, 6"
* radius curves and has been tested with Zumos using 30:1 HP and
* 75:1 HP motors. Modifications might be required for it to work
* well on different courses or with different motors.
*
* https://www.pololu.com/catalog/product/2506
* https://www.pololu.com
* https://forum.pololu.com
*/
#include <Wire.h>
#include <ZumoShield.h>
ZumoBuzzer buzzer;
ZumoReflectanceSensorArray reflectanceSensors;
ZumoMotors motors;
Pushbutton button(ZUMO_BUTTON);
int lastError = 0;
// This is the maximum speed the motors will be allowed to turn.
// (400 lets the motors go at top speed; decrease to impose a speed limit)
const int MAX_SPEED = 400;
void setup()
{
// Play a little welcome song
buzzer.play(">g32>>c32");
// Initialize the reflectance sensors module
reflectanceSensors.init();
// Wait for the user button to be pressed and released
button.waitForButton();
// Turn on LED to indicate we are in calibration mode
pinMode(13, OUTPUT);
digitalWrite(13, HIGH);
// Wait 1 second and then begin automatic sensor calibration
// by rotating in place to sweep the sensors over the line
delay(1000);
int i;
for(i = 0; i < 80; i++)
{
if ((i > 10 && i <= 30) || (i > 50 && i <= 70))
motors.setSpeeds(-200, 200);
else
motors.setSpeeds(200, -200);
reflectanceSensors.calibrate();
// Since our counter runs to 80, the total delay will be
// 80*20 = 1600 ms.
delay(20);
}
motors.setSpeeds(0,0);
// Turn off LED to indicate we are through with calibration
digitalWrite(13, LOW);
buzzer.play(">g32>>c32");
// Wait for the user button to be pressed and released
button.waitForButton();
// Play music and wait for it to finish before we start driving.
buzzer.play("L16 cdegreg4");
while(buzzer.isPlaying());
}
void loop()
{
unsigned int sensors[6];
// Get the position of the line. Note that we *must* provide the "sensors"
// argument to readLine() here, even though we are not interested in the
// individual sensor readings
int position = reflectanceSensors.readLine(sensors);
// Our "error" is how far we are away from the center of the line, which
// corresponds to position 2500.
int error = position - 2500;
// Get motor speed difference using proportional and derivative PID terms
// (the integral term is generally not very useful for line following).
// Here we are using a proportional constant of 1/4 and a derivative
// constant of 6, which should work decently for many Zumo motor choices.
// You probably want to use trial and error to tune these constants for
// your particular Zumo and line course.
int speedDifference = error / 4 + 6 * (error - lastError);
lastError = error;
// Get individual motor speeds. The sign of speedDifference
// determines if the robot turns left or right.
int m1Speed = MAX_SPEED + speedDifference;
int m2Speed = MAX_SPEED - speedDifference;
// Here we constrain our motor speeds to be between 0 and MAX_SPEED.
// Generally speaking, one motor will always be turning at MAX_SPEED
// and the other will be at MAX_SPEED-|speedDifference| if that is positive,
// else it will be stationary. For some applications, you might want to
// allow the motor speed to go negative so that it can spin in reverse.
if (m1Speed < 0)
m1Speed = 0;
if (m2Speed < 0)
m2Speed = 0;
if (m1Speed > MAX_SPEED)
m1Speed = MAX_SPEED;
if (m2Speed > MAX_SPEED)
m2Speed = MAX_SPEED;
motors.setSpeeds(m1Speed, m2Speed);
}