12 static bool flipLeft =
false;
13 static bool flipRight =
false;
16 void Zumo32U4Motors::init2()
18 FastGPIO::Pin<PWM_L>::setOutputLow();
19 FastGPIO::Pin<PWM_R>::setOutputLow();
20 FastGPIO::Pin<DIR_L>::setOutputLow();
21 FastGPIO::Pin<DIR_R>::setOutputLow();
69 FastGPIO::Pin<DIR_L>::setOutput(reverse ^ flipLeft);
91 FastGPIO::Pin<DIR_R>::setOutput(reverse ^ flipRight);
static void flipLeftMotor(bool flip)
Flips the direction of the left motor.
static void setRightSpeed(int16_t speed)
Sets the speed for the right motor.
static void flipRightMotor(bool flip)
Flips the direction of the right motor.
static void setLeftSpeed(int16_t speed)
Sets the speed for the left motor.
static void setSpeeds(int16_t leftSpeed, int16_t rightSpeed)
Sets the speeds for both motors.