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
18 int right_motor_forward_pin
= 3;
20 int right_motor_backward_pin
= 4;
22 int right_motor_speed_pin
= 5;
25 int right_echo_pin
= 6;
27 int right_trigger_pin
= 7;
31 int left_motor_forward_pin
= 8;
33 int left_motor_backward_pin
= 9;
35 int left_motor_speed_pin
= 10;
38 int left_echo_pin
= 11;
40 int left_trigger_pin
= 12;
43 digitalWrite(pin
, HIGH
);}
46 digitalWrite(pin
, LOW
);}
48 void set_motor(int speed_pin
,
62 // since speed has been set positive, no need to check if speed < -255.
65 analogWrite(speed_pin
, speed
);}
67 void go(int left_motor_speed
, int right_motor_speed
){
68 set_motor(left_motor_speed_pin
,
69 left_motor_forward_pin
,
70 left_motor_backward_pin
,
72 set_motor(right_motor_speed_pin
,
73 right_motor_forward_pin
,
74 right_motor_backward_pin
,
77 int ping(int trigger
, int echo
){
82 // turn on the trigger and leave it on long enough for the
83 // sonar sensor to notice
85 delayMicroseconds(10);
87 ping_time
= pulseIn(echo
, HIGH
);
90 // sonar needs some time to recover before pinging again,
91 // so make sure it gets enough sleep right here. 50 milliseconds
98 pinMode(right_motor_speed_pin
, OUTPUT
);
99 pinMode(right_motor_forward_pin
, OUTPUT
);
100 pinMode(right_motor_backward_pin
, OUTPUT
);
102 pinMode(right_echo_pin
, INPUT
);
103 pinMode(right_trigger_pin
, OUTPUT
);
105 pinMode(left_motor_speed_pin
, OUTPUT
);
106 pinMode(left_motor_forward_pin
, OUTPUT
);
107 pinMode(left_motor_backward_pin
, OUTPUT
);
109 pinMode(left_echo_pin
, INPUT
);
110 pinMode(left_trigger_pin
, OUTPUT
);
112 off(left_motor_speed_pin
);
113 off(left_motor_forward_pin
);
114 off(left_motor_backward_pin
);
115 off(left_trigger_pin
);
117 off(right_motor_speed_pin
);
118 off(right_motor_forward_pin
);
119 off(right_motor_backward_pin
);
120 off(right_trigger_pin
); }
126 // you'll need to adjust these based on your sonar sensor's behavior
127 int desired_right_ping_time
= 800;
128 int desired_left_ping_time
= 800;
130 unsigned int actual_left_ping_time
= ping(left_trigger_pin
, left_echo_pin
);
131 unsigned int actual_right_ping_time
= ping(right_trigger_pin
, right_echo_pin
);
133 left_speed
= actual_left_ping_time
- desired_left_ping_time
;
134 right_speed
= actual_right_ping_time
- desired_right_ping_time
;
136 Serial
.print("left: ping = ");
137 Serial
.print(actual_left_ping_time
);
138 Serial
.print(" speed = ");
139 Serial
.print(left_speed
);
140 Serial
.print(" right: ping = ");
141 Serial
.print(actual_right_ping_time
);
142 Serial
.print(" speed = ");
143 Serial
.print(right_speed
);
146 go(left_speed
, right_speed
); }