|
|
|
// This is the library for the TB6612 that contains the class Motor and all the |
|
// functions |
|
#include <SparkFun_TB6612.h> |
|
|
|
// Pins for all inputs, keep in mind the PWM defines must be on PWM pins |
|
// the default pins listed are the ones used on the Redbot (ROB-12097) with |
|
// the exception of STBY which the Redbot controls with a physical switch |
|
|
|
#define PWMA 16 |
|
#define AIN2 5 |
|
#define AIN1 4 |
|
#define BIN1 14 |
|
#define BIN2 2 |
|
#define PWMB 0 |
|
|
|
#define STBY 100 |
|
#define SNSRL 12 |
|
#define SNSRR 10 |
|
#define TRIG 15 |
|
#define ECHO 13 |
|
|
|
// these constants are used to allow you to make your motor configuration |
|
// line up with function names like forward. Value can be 1 or -1 |
|
const int offsetA = 1; |
|
const int offsetB = 1; |
|
const float speedOfSound = .0343; |
|
const int maxDistance = 40; |
|
|
|
// Initializing motors. The library will allow you to initialize as many |
|
// motors as you have memory for. If you are using functions like forward |
|
// that take 2 motors as arguements you can either write new functions or |
|
// call the function more than once. |
|
Motor motor1 = Motor(AIN1, AIN2, PWMA, offsetA, STBY); |
|
Motor motor2 = Motor(BIN1, BIN2, PWMB, offsetB, STBY); |
|
|
|
void setup() |
|
{ |
|
pinMode(TRIG,OUTPUT); |
|
pinMode(ECHO,INPUT); |
|
pinMode(SNSRL,INPUT); |
|
pinMode(SNSRR,INPUT); |
|
Serial.begin(9600); |
|
} |
|
|
|
float getDistance() { |
|
digitalWrite(TRIG, LOW); |
|
delay(2); |
|
digitalWrite(TRIG, HIGH); |
|
delay(10); |
|
digitalWrite(TRIG, LOW); |
|
return ( pulseIn(ECHO, HIGH) * speedOfSound) / 2; |
|
} |
|
|
|
void loop() { |
|
Serial.println("distance"); |
|
float distance = getDistance(); |
|
Serial.println(distance); |
|
int rightSensor = digitalRead(SNSRR); |
|
int leftSensor = digitalRead(SNSRL); |
|
Serial.println(leftSensor); |
|
Serial.println(rightSensor); |
|
|
|
// Found opponent |
|
if (getDistance() < maxDistance && (leftSensor && rightSensor)) { |
|
Serial.println("Attack!"); |
|
brake(motor1, motor2); |
|
forward(motor1, motor2); |
|
} else { |
|
// Both sensors found edge or mat, back up quickly and turn around |
|
if (!leftSensor && !rightSensor) { |
|
Serial.println("DANGER!"); |
|
brake(motor1, motor2); |
|
back(motor1, motor2, 250); |
|
delay(800); |
|
left(motor1, motor2, 250); |
|
delay(400); |
|
// push forward slowly |
|
forward(motor1, motor2, 150); |
|
} |
|
|
|
// The left sensor found the edge, back up a bit and turn RIGHT quickly |
|
if (!leftSensor && rightSensor) { |
|
Serial.println("LEFT WARNING"); |
|
brake(motor1, motor2); |
|
back(motor1, motor2, 250); |
|
delay(200); |
|
right(motor1, motor2, 250); |
|
delay(300); |
|
// push forward slowly and seek |
|
forward(motor1, motor2, 150); |
|
} |
|
// The right sensor found the edge, back up a bit and turn LEFT quickly |
|
if (leftSensor && !rightSensor) { |
|
Serial.println("RIGHT WARNING"); |
|
brake(motor1, motor2); |
|
back(motor1, motor2, 250); |
|
delay(200); |
|
left(motor1, motor2, 250); |
|
delay(300); |
|
// Push forward slowly and seek |
|
forward(motor1, motor2, 150); |
|
} |
|
|
|
// Not at the edge, somewhere in the mat, seek for opponent |
|
if (leftSensor && rightSensor) { |
|
Serial.println("SEEKING..."); |
|
brake(motor1, motor2); |
|
left(motor1, motor2, 250); |
|
delay(600); |
|
if (getDistance() < 40) { |
|
forward(motor1, motor2, 150); |
|
} else { |
|
right(motor1, motor2, 250); |
|
delay(200); |
|
if (getDistance() < 40) { |
|
forward(motor1, motor2, 150); |
|
} else { |
|
right(motor1, motor2, 250); |
|
// Done checking, let the loop start up again and assume |
|
// the initial check will take over |
|
} |
|
} |
|
|
|
} |
|
} |
|
} |