remove unused backup and turn_around in follow
[challenge-bot] / build-stages / g_follow / g_follow.ino
1 /*
2 This program is free software: you can redistribute it and/or modify
3 it under the terms of the GNU Affero General Public License as
4 published by the Free Software Foundation, either version 3 of the
5 License, or (at your option) any later version.
6
7 This program is distributed in the hope that it will be useful,
8 but WITHOUT ANY WARRANTY; without even the implied warranty of
9 MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10 GNU Affero General Public License for more details.
11
12 You should have received a copy of the GNU Affero General Public License
13 along with this program. If not, see <http://www.gnu.org/licenses/>.
14 */
15
16 // define which pins are connected to which components
17 int right_motor_forward_pin = 3;
18 int right_motor_backward_pin = 4;
19 int right_motor_speed_pin = 5;
20
21 int right_echo_pin = 6;
22 int right_trigger_pin = 7;
23
24 int left_motor_forward_pin = 8;
25 int left_motor_backward_pin = 9;
26 int left_motor_speed_pin = 10;
27
28 int left_echo_pin = 11;
29 int left_trigger_pin = 12;
30
31 void on(int pin){
32 digitalWrite(pin, HIGH);}
33
34 void off(int pin){
35 digitalWrite(pin, LOW);}
36
37 void set_motor(int speed_pin,
38 int forward_pin,
39 int backward_pin,
40 int speed){
41 if(speed > 0){
42 off(backward_pin);
43 on(forward_pin);}
44 else if(speed < 0){
45 off(forward_pin);
46 on(backward_pin);
47 speed = -speed;}
48 else{ // speed is 0
49 off(forward_pin);
50 off(backward_pin);}
51 // since speed has been set positive, no need to check if speed < -255.
52 if(speed > 255){
53 speed = 255;}
54 analogWrite(speed_pin, speed);}
55
56 void go(int left_motor_speed, int right_motor_speed){
57 set_motor(left_motor_speed_pin,
58 left_motor_forward_pin,
59 left_motor_backward_pin,
60 left_motor_speed);
61 set_motor(right_motor_speed_pin,
62 right_motor_forward_pin,
63 right_motor_backward_pin,
64 right_motor_speed);}
65
66 int ping(int trigger, int echo){
67 int ping_time = 0;
68 // turn off trigger
69 off(trigger);
70 delayMicroseconds(2);
71 // turn on the trigger and leave it on long enough for the
72 // sonar sensor to notice
73 on(trigger);
74 delayMicroseconds(10);
75 off(trigger);
76 ping_time = pulseIn(echo, HIGH);
77 if(ping_time <= 0){
78 ping_time = 3000;}
79 // sonar needs some time to recover before pinging again,
80 // so make sure it gets enough sleep right here. 50 milliseconds
81 delay(50);
82 return ping_time;}
83
84 void setup(){
85 Serial.begin(9600);
86
87 pinMode(right_motor_speed_pin, OUTPUT);
88 pinMode(right_motor_forward_pin, OUTPUT);
89 pinMode(right_motor_backward_pin, OUTPUT);
90
91 pinMode(right_echo_pin, INPUT);
92 pinMode(right_trigger_pin, OUTPUT);
93
94 pinMode(left_motor_speed_pin, OUTPUT);
95 pinMode(left_motor_forward_pin, OUTPUT);
96 pinMode(left_motor_backward_pin, OUTPUT);
97
98 pinMode(left_echo_pin, INPUT);
99 pinMode(left_trigger_pin, OUTPUT);
100
101 off(left_motor_speed_pin);
102 off(left_motor_forward_pin);
103 off(left_motor_backward_pin);
104 off(left_trigger_pin);
105
106 off(right_motor_speed_pin);
107 off(right_motor_forward_pin);
108 off(right_motor_backward_pin);
109 off(right_trigger_pin); }
110
111 void loop() {
112 int left_speed;
113 int right_speed;
114
115 // you'll need to adjust these based on your sonar sensor's behavior
116 int desired_right_ping_time = 800;
117 int desired_left_ping_time = 800;
118
119 unsigned int actual_left_ping_time = ping(left_trigger_pin, left_echo_pin);
120 unsigned int actual_right_ping_time = ping(right_trigger_pin, right_echo_pin);
121
122 left_speed = actual_left_ping_time - desired_left_ping_time;
123 right_speed = actual_right_ping_time - desired_right_ping_time;
124
125 Serial.print("left: ping = ");
126 Serial.print(actual_left_ping_time);
127 Serial.print(" speed = ");
128 Serial.print(left_speed);
129 Serial.print(" right: ping = ");
130 Serial.print(actual_right_ping_time);
131 Serial.print(" speed = ");
132 Serial.print(right_speed);
133 Serial.println();
134
135 go(left_speed, right_speed); }