8 #if defined(__AVR_ATmega168__) || defined(__AVR_ATmega328P__) || defined (__AVR_ATmega32U4__)
12 static boolean flipLeft =
false;
13 static boolean flipRight =
false;
16 ZumoMotors::ZumoMotors()
21 void ZumoMotors::init2()
23 pinMode(PWM_L, OUTPUT);
24 pinMode(PWM_R, OUTPUT);
25 pinMode(DIR_L, OUTPUT);
26 pinMode(DIR_R, OUTPUT);
44 void ZumoMotors::flipLeftMotor(
boolean flip)
50 void ZumoMotors::flipRightMotor(
boolean flip)
56 void ZumoMotors::setLeftSpeed(
int speed)
73 analogWrite(PWM_L, speed * 51 / 80);
76 if (reverse ^ flipLeft)
77 digitalWrite(DIR_L, HIGH);
79 digitalWrite(DIR_L, LOW);
83 void ZumoMotors::setRightSpeed(
int speed)
100 analogWrite(PWM_R, speed * 51 / 80);
103 if (reverse ^ flipRight)
104 digitalWrite(DIR_R, HIGH);
106 digitalWrite(DIR_R, LOW);
110 void ZumoMotors::setSpeeds(
int leftSpeed,
int rightSpeed)
112 setLeftSpeed(leftSpeed);
113 setRightSpeed(rightSpeed);