make comments match code for stay on table
[challenge-bot] / build-stages / h_stay_on_table / h_stay_on_table.ino
CommitLineData
fa6c6440 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
7c21fba2 17int right_motor_forward_pin = 3;
18int right_motor_backward_pin = 4;
19int right_motor_speed_pin = 5;
fa6c6440 20
5218c75f 21int right_echo_pin = 6;
22int right_trigger_pin = 7;
fa6c6440 23
34a3efe6 24int left_motor_forward_pin = 8;
25int left_motor_backward_pin = 9;
26int left_motor_speed_pin = 10;
fa6c6440 27
5218c75f 28int left_echo_pin = 11;
29int left_trigger_pin = 12;
fa6c6440 30
31void on(int pin){
32 digitalWrite(pin, HIGH);}
33
34void off(int pin){
35 digitalWrite(pin, LOW);}
36
37void 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);}
d77c514c 51 // since speed has been set positive, no need to check if speed < -255.
fa6c6440 52 if(speed > 255){
53 speed = 255;}
54 analogWrite(speed_pin, speed);}
55
56void 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
66int 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
84void backup(int backup_time){
85 go(-250, -250);
86 delay(backup_time);}
87
88void turn_around(int turn_around_time){
89 go(-250, 250);
90 delay(turn_around_time);}
91
92void setup(){
93 Serial.begin(9600);
94
95 pinMode(right_motor_speed_pin, OUTPUT);
96 pinMode(right_motor_forward_pin, OUTPUT);
97 pinMode(right_motor_backward_pin, OUTPUT);
98
99 pinMode(right_echo_pin, INPUT);
100 pinMode(right_trigger_pin, OUTPUT);
101
102 pinMode(left_motor_speed_pin, OUTPUT);
103 pinMode(left_motor_forward_pin, OUTPUT);
104 pinMode(left_motor_backward_pin, OUTPUT);
105
106 pinMode(left_echo_pin, INPUT);
107 pinMode(left_trigger_pin, OUTPUT);
108
109 off(left_motor_speed_pin);
110 off(left_motor_forward_pin);
111 off(left_motor_backward_pin);
112 off(left_trigger_pin);
113
114 off(right_motor_speed_pin);
115 off(right_motor_forward_pin);
116 off(right_motor_backward_pin);
117 off(right_trigger_pin);}
118
119void loop(){
120 int left_speed;
121 int right_speed;
122
123 int forward_speed = 250;
124 int stop_speed = 0;
125
126 // adjust this number as necessary for your robot.
127 // it represents how far the table is from your sonar sensor.
b3ab14a7 128 // larger values mean larger distance. default is 800
129 int right_max_ping_time_over_table = 800;
130 int left_max_ping_time_over_table = 800;
fa6c6440 131 int backup_time = 2000;
132 // the exact amount of time for turning around might need
133 // twerking for your robot. the default value is 3200
b3ab14a7 134 int turn_around_time = 3200;
fa6c6440 135
136 int actual_left_ping_time = ping(left_trigger_pin, left_echo_pin);
137 int actual_right_ping_time = ping(right_trigger_pin, right_echo_pin);
138
139 Serial.print("left ping = ");
140 Serial.print(actual_left_ping_time);
141 Serial.print("\tright_ping = ");
142 Serial.println(actual_right_ping_time);
143
144 // if the left sonar senses a table, keep driving left side forward,
145 // otherwise, stop left side
146 if(actual_left_ping_time < left_max_ping_time_over_table){
147 left_speed = forward_speed;}
148 else{
149 left_speed = stop_speed;}
150 // if the right sonar senses a table, keep driving right side forward,
151 // otherwise, stop right side
152 if(actual_right_ping_time < right_max_ping_time_over_table){
153 right_speed = forward_speed;}
154 else{
155 right_speed = stop_speed;}
156
157 // if both sonars detect being off the table, backup and turn around
158 // otherwise, go the correct speed for each wheel
159 if(actual_left_ping_time >= left_max_ping_time_over_table
160 && actual_right_ping_time >= right_max_ping_time_over_table){
161 Serial.println("backing up");
162 backup(backup_time);
163 Serial.println("turning around");
164 turn_around(turn_around_time);}
165 else{
166 Serial.println("going");
167 go(left_speed, right_speed);}}