define wiring in separate file
[challenge-bot] / build-stages / h_stay_on_table / h_stay_on_table.ino
index 07f7d17230591bea8820e73851b23957ac8f1512..fcdfa34315ab83cd214dbfb4434b7958c36a7f14 100644 (file)
     along with this program.  If not, see <http://www.gnu.org/licenses/>.
  */
 
-// define which pins are connected to which components
-int right_motor_speed_pin = 3;
-int right_motor_forward_pin = 4;
-int right_motor_backward_pin = 5;
-
-int right_echo_pin = 6;
-int right_trigger_pin = 7;
-
-int left_motor_speed_pin = 8;
-int left_motor_forward_pin = 9;
-int left_motor_backward_pin = 10;
-
-int left_echo_pin = 11;
-int left_trigger_pin = 12;
+#include "bot_map.h"
 
 void on(int pin){
   digitalWrite(pin, HIGH);}
@@ -48,6 +35,7 @@ void set_motor(int speed_pin,
   else{ // speed is 0
     off(forward_pin);
     off(backward_pin);}
+  // since speed has been set positive, no need to check if speed < -255.
   if(speed > 255){
     speed = 255;}
   analogWrite(speed_pin, speed);}
@@ -124,17 +112,28 @@ void loop(){
 
   // adjust this number as necessary for your robot.
   // it represents how far the table is from your sonar sensor.
-  // larger values mean larger distance.  default is 400
-  int right_max_ping_time_over_table = 500;
-  int left_max_ping_time_over_table = 500;
-  int backup_time = 2000;
+  // larger values mean larger distance.  default is 800
+  int right_max_ping_time_over_table = 800;
+  int left_max_ping_time_over_table = 800;
+  int backup_time = 1000;
   // the exact amount of time for turning around might need
   // twerking for your robot.  the default value is 3200
-  int turn_around_time = 2133;
+  int turn_around_time = 3200;
 
   int actual_left_ping_time = ping(left_trigger_pin, left_echo_pin);
   int actual_right_ping_time = ping(right_trigger_pin, right_echo_pin);
 
+  /* int left_led_value = (int)(actual_left_ping_time / 16.0); */
+  /* int right_led_value = (int)(actual_right_ping_time / 16.0); */
+
+  /* Serial.print("left led value = "); */
+  /* Serial.print(left_led_value); */
+  /* Serial.print(", right led value = "); */
+  /* Serial.print(right_led_value); */
+
+  /* analogWrite(left_led_pin, left_led_value); */
+  /* analogWrite(right_led_pin, right_led_value); */
+
   Serial.print("left ping = ");
   Serial.print(actual_left_ping_time);
   Serial.print("\tright_ping = ");