Zumo32U4 library
Static Public Member Functions | List of all members
Zumo32U4Motors Class Reference

Controls motor speed and direction on the Zumo 32U4. More...

#include <Zumo32U4Motors.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 speeds for both motors. More...
 

Detailed Description

Controls motor speed and direction on the Zumo 32U4.

This library uses Timer 1, so it will conflict with any other libraries using that timer.

Definition at line 13 of file Zumo32U4Motors.h.

Member Function Documentation

◆ flipLeftMotor()

void Zumo32U4Motors::flipLeftMotor ( bool  flip)
static

Flips the direction of the left motor.

You can call this function with an argument of true if the left motor of your Zumo was not installed in the standard way and you want a positive speed argument to correspond to forward movement.

Parameters
flipIf 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 39 of file Zumo32U4Motors.cpp.

◆ flipRightMotor()

void Zumo32U4Motors::flipRightMotor ( bool  flip)
static

Flips the direction of the right motor.

You can call this function with an argument of true if the right motor of your Zumo was not installed in the standard way and you want a positive speed argument to correspond to forward movement.

Parameters
flipIf 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 Zumo32U4Motors.cpp.

◆ setLeftSpeed()

void Zumo32U4Motors::setLeftSpeed ( int16_t  speed)
static

Sets the speed for the left motor.

Parameters
speedA number from -400 to 400 representing the speed and direction of the left motor. Values of -400 or less result in full speed reverse, and values of 400 or more result in full speed forward.

Definition at line 51 of file Zumo32U4Motors.cpp.

◆ setRightSpeed()

void Zumo32U4Motors::setRightSpeed ( int16_t  speed)
static

Sets the speed for the right motor.

Parameters
speedA number from -400 to 400 representing the speed and direction of the right motor. Values of -400 or less result in full speed reverse, and values of 400 or more result in full speed forward.

Definition at line 73 of file Zumo32U4Motors.cpp.

◆ setSpeeds()

void Zumo32U4Motors::setSpeeds ( int16_t  leftSpeed,
int16_t  rightSpeed 
)
static

Sets the speeds for both motors.

Parameters
leftSpeedA number from -400 to 400 representing the speed and direction of the right motor. Values of -400 or less result in full speed reverse, and values of 400 or more result in full speed forward.
rightSpeedA number from -400 to 400 representing the speed and direction of the right motor. Values of -400 or less result in full speed reverse, and values of 400 or more result in full speed forward.

Definition at line 95 of file Zumo32U4Motors.cpp.


The documentation for this class was generated from the following files: