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.
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.
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/>.
16 // define which pins are connected to which components
17 int right_motor_speed_pin
= 3;
18 int right_motor_forward_pin
= 4;
19 int right_motor_backward_pin
= 5;
21 int right_echo_pin
= 6;
22 int right_trigger_pin
= 7;
24 int left_motor_forward_pin
= 8;
25 int left_motor_backward_pin
= 9;
26 int left_motor_speed_pin
= 10;
28 int left_echo_pin
= 11;
29 int left_trigger_pin
= 12;
32 digitalWrite(pin
, HIGH
);}
35 digitalWrite(pin
, LOW
);}
37 void set_motor(int speed_pin
,
53 analogWrite(speed_pin
, speed
);}
55 void go(int left_motor_speed
, int right_motor_speed
){
56 set_motor(left_motor_speed_pin
,
57 left_motor_forward_pin
,
58 left_motor_backward_pin
,
60 set_motor(right_motor_speed_pin
,
61 right_motor_forward_pin
,
62 right_motor_backward_pin
,
65 int ping(int trigger
, int echo
){
70 // turn on the trigger and leave it on long enough for the
71 // sonar sensor to notice
73 delayMicroseconds(10);
75 ping_time
= pulseIn(echo
, HIGH
);
78 // sonar needs some time to recover before pinging again,
79 // so make sure it gets enough sleep right here. 50 milliseconds
83 void backup(int backup_time
){
87 void turn_around(int turn_around_time
){
89 delay(turn_around_time
);}
94 pinMode(right_motor_speed_pin
, OUTPUT
);
95 pinMode(right_motor_forward_pin
, OUTPUT
);
96 pinMode(right_motor_backward_pin
, OUTPUT
);
98 pinMode(right_echo_pin
, INPUT
);
99 pinMode(right_trigger_pin
, OUTPUT
);
101 pinMode(left_motor_speed_pin
, OUTPUT
);
102 pinMode(left_motor_forward_pin
, OUTPUT
);
103 pinMode(left_motor_backward_pin
, OUTPUT
);
105 pinMode(left_echo_pin
, INPUT
);
106 pinMode(left_trigger_pin
, OUTPUT
);
108 off(left_motor_speed_pin
);
109 off(left_motor_forward_pin
);
110 off(left_motor_backward_pin
);
111 off(left_trigger_pin
);
113 off(right_motor_speed_pin
);
114 off(right_motor_forward_pin
);
115 off(right_motor_backward_pin
);
116 off(right_trigger_pin
);}
122 int forward_speed
= 250;
125 // adjust this number as necessary for your robot.
126 // it represents how far the table is from your sonar sensor.
127 // larger values mean larger distance. default is 400
128 int right_max_ping_time_over_table
= 500;
129 int left_max_ping_time_over_table
= 500;
130 int backup_time
= 2000;
131 // the exact amount of time for turning around might need
132 // twerking for your robot. the default value is 3200
133 int turn_around_time
= 2133;
135 int actual_left_ping_time
= ping(left_trigger_pin
, left_echo_pin
);
136 int actual_right_ping_time
= ping(right_trigger_pin
, right_echo_pin
);
138 Serial
.print("left ping = ");
139 Serial
.print(actual_left_ping_time
);
140 Serial
.print("\tright_ping = ");
141 Serial
.println(actual_right_ping_time
);
143 // if the left sonar senses a table, keep driving left side forward,
144 // otherwise, stop left side
145 if(actual_left_ping_time
< left_max_ping_time_over_table
){
146 left_speed
= forward_speed
;}
148 left_speed
= stop_speed
;}
149 // if the right sonar senses a table, keep driving right side forward,
150 // otherwise, stop right side
151 if(actual_right_ping_time
< right_max_ping_time_over_table
){
152 right_speed
= forward_speed
;}
154 right_speed
= stop_speed
;}
156 // if both sonars detect being off the table, backup and turn around
157 // otherwise, go the correct speed for each wheel
158 if(actual_left_ping_time
>= left_max_ping_time_over_table
159 && actual_right_ping_time
>= right_max_ping_time_over_table
){
160 Serial
.println("backing up");
162 Serial
.println("turning around");
163 turn_around(turn_around_time
);}
165 Serial
.println("going");
166 go(left_speed
, right_speed
);}}