#ifndef FILE_3DOT_SEEN #define FILE_3DOT_SEEN /* Mapping for 9.10b "Texas" */ /* IR Sensors */ #define WHITE LOW #define BLACK HIGH #define IR_R_O A0 // IR_R_O = analog pin A0 #define IR_R_I A1 #define IR_L_I A2 #define IR_L_O A3 /* Motors */ #define AIN1 6 #define AIN2 9 #define NSLEEP 4 #define BIN1 5 #define BIN2 10 /* v10.1 const int AIN1 = 11 // PB7, const int AIN2 = 6 // PD7, OC4D const int BIN1 = 13 // PC7, OC4A const int BIN2 = 10 // PB6, OC4B /* Wheel Encoder */ const int EncoderA = 14; // MISO const int EncoderB = 16; // MOSI /* Motor PWM experimentally determined values in Lab 2 */ const int motorRightHIGH = 240; const int motorLeftHIGH = 230; /* IR sensor constants experimentally determined values in Lab 3 * to determine trigger points * hysterisis = 300 - 80 = 220 / 2 = 110 * trigger0 = 80 + 110/2 = 135 * trigger1 = 300 - 110/2 = 245 */ const uint16_t trigger1 = 245; // IR values 1023 to 300 = 1 (black) const uint16_t trigger0 = 135; // IR values 80 to 0 = 0 (white) void init3DoT() { /* Initialize the Motor Driver */ pinMode(AIN1,OUTPUT); // Left Motor Digital pin AIN1 is an output digitalWrite(AIN1,LOW); // Left Motor OFF pinMode(AIN2,OUTPUT); // Left Motor Digital pin AIN2 is an output digitalWrite(AIN2,LOW); // Left Motor OFF pinMode(NSLEEP,OUTPUT); // Motor Sleep pin digitalWrite(NSLEEP,HIGH); // Wake-up pinMode(BIN1,OUTPUT); // Right Motor Digital pin BIN1 is an output digitalWrite(BIN1,LOW); // Right Motor OFF pinMode(BIN2,OUTPUT); // Right Motor Digital pin BIN2 is an output digitalWrite(BIN2,LOW); // Right Motor OFF /* Initialize the IR Sensors */ pinMode(IR_R_O,INPUT); // Analog pin A0 pinMode(IR_R_I,INPUT); // Analog pin A1 pinMode(IR_L_I,INPUT); // Analog pin A2 pinMode(IR_L_O,INPUT); // Analog pin A3 /* Wheel Encoder */ pinMode(EncoderA, INPUT); // pull-up included on wheel encoder pinMode(EncoderB, INPUT); /* ADC Reference voltage */ analogReference(INTERNAL); // reference voltage = 2.56v }; /* based on v9_motor_test_basic */ typedef enum { // 0 1 2 3 4 brake, forward, backward, spin_right, spin_left } drv8848_t; /* alternate form 0 1 2 3 4 enum drv8848_t {brake, forward, backward, spin_right, spin_left}; */ void setMotor(drv8848_t state){ switch(state) { case brake: // motors initialized to brake analogWrite(AIN1, 255); // "true" A ==> left motor (simply a convention) analogWrite(AIN2, 255); analogWrite(BIN1, 255); // right motor analogWrite(BIN2, 255); break; case forward: // motors initialized to standby mode (coast) analogWrite(AIN1, 0); // "true" A ==> left motor (simply a convention) analogWrite(AIN2, 230); analogWrite(BIN1, 0); // right motor analogWrite(BIN2, 230); break; case backward: // motors intialized to standby mode (brake) analogWrite(AIN1, 230); analogWrite(AIN2, 0); analogWrite(BIN1, 230); analogWrite(BIN2, 0); break; case spin_right: // motors initialized to standby mode (motor A = coast, B = brake) analogWrite(AIN1, 0); analogWrite(AIN2, 230); analogWrite(BIN1, 230); analogWrite(BIN2, 0); break; case spin_left: // motors initialized to standby mode (motor A = brake, B = coast) analogWrite(AIN1, 230); analogWrite(AIN2, 0); analogWrite(BIN1, 0); analogWrite(BIN2, 230); break; default: break; } } #endif /* !FILE_3DOT_SEEN */