Romi32U4 library
|
Controls motor speed and direction on the Romi 32U4. More...
#include <Romi32U4Motors.h>
Static Public Member Functions | |
static void | flipLeftMotor (bool flip) |
Flips the direction of the left motor. More... | |
static void | flipRightMotor (bool flip) |
Flips the direction of the right motor. More... | |
static void | setLeftSpeed (int16_t speed) |
Sets the speed for the left motor. More... | |
static void | setRightSpeed (int16_t speed) |
Sets the speed for the right motor. More... | |
static void | setSpeeds (int16_t leftSpeed, int16_t rightSpeed) |
Sets the speed for both motors. More... | |
static void | allowTurbo (bool turbo) |
Turns turbo mode on or off. More... | |
Controls motor speed and direction on the Romi 32U4.
This library uses Timer 1, so it will conflict with any other libraries using that timer.
Definition at line 13 of file Romi32U4Motors.h.
|
static |
Turns turbo mode on or off.
By default turbo mode is off. When turbo mode is on, the range of speeds accepted by the other functions in this library becomes -400 to 400 (instead of -300 to 300). Turning turbo mode on allows the Romi to move faster but could decrease the lifetime of the motors.
This function does not have any immediate effect on the speed of the motors; it just changes the behavior of the other functions in this library.
turbo | If true, turns turbo mode on. If false, turns turbo mode off. |
Definition at line 98 of file Romi32U4Motors.cpp.
|
static |
Flips the direction of the left motor.
You can call this function with an argument of true
if the left motor of your Romi was not wired in the standard way and you want a positive speed argument to correspond to forward movement.
flip | If true, then positive motor speeds will correspond to the direction pin being high. If false, then positive motor speeds will correspond to the direction pin being low. |
Definition at line 40 of file Romi32U4Motors.cpp.
|
static |
Flips the direction of the right motor.
You can call this function with an argument of true
if the right motor of your Romi was not wired in the standard way and you want a positive speed argument to correspond to forward movement.
flip | If true, then positive motor speeds will correspond to the direction pin being high. If false, then positive motor speeds will correspond to the direction pin being low. |
Definition at line 45 of file Romi32U4Motors.cpp.
|
static |
Sets the speed for the left motor.
speed | A number from -300 to 300 representing the speed and direction of the left motor. Values of -300 or less result in full speed reverse, and values of 300 or more result in full speed forward. |
Definition at line 50 of file Romi32U4Motors.cpp.
|
static |
Sets the speed for the right motor.
speed | A number from -300 to 300 representing the speed and direction of the right motor. Values of -300 or less result in full speed reverse, and values of 300 or more result in full speed forward. |
Definition at line 71 of file Romi32U4Motors.cpp.
|
static |
Sets the speed for both motors.
leftSpeed | A number from -300 to 300 representing the speed and direction of the right motor. Values of -300 or less result in full speed reverse, and values of 300 or more result in full speed forward. |
rightSpeed | A number from -300 to 300 representing the speed and direction of the right motor. Values of -300 or less result in full speed reverse, and values of 300 or more result in full speed forward. |
Definition at line 92 of file Romi32U4Motors.cpp.