wpi-32u4-library
Public Member Functions | Static Public Member Functions | Protected Types | Protected Member Functions | Static Protected Member Functions | Protected Attributes | Friends
Romi32U4Motor Class Referenceabstract

#include <Romi32U4Motors.h>

Inherited by LeftMotor, and RightMotor.

Public Member Functions

 Romi32U4Motor (void)
 
void setPIDCoeffients (float kp, float ki)
 
void allowTurbo (bool turbo)
 Turns turbo mode on or off. More...
 
void handleISR (bool newA, bool newB)
 

Static Public Member Functions

static void init ()
 

Protected Types

enum  CTRL_MODE : uint8_t { CTRL_DIRECT , CTRL_SPEED , CTRL_POS }
 

Protected Member Functions

virtual void setEffort (int16_t effort)=0
 Sets the effort for the motor directly. Overloaded for the left and right motors. Use Chassis::setEfforts() from the user code to control motor efforts directly. More...
 
int16_t getCount (void)
 
int16_t getAndResetCount (void)
 
void setTargetSpeed (float targetSpeed)
 
void moveFor (int16_t amount)
 
bool checkComplete (void)
 
void update (void)
 
void calcEncoderDelta (void)
 

Static Protected Member Functions

static void initMotors ()
 
static void initEncoders ()
 

Protected Attributes

volatile CTRL_MODE ctrlMode = CTRL_DIRECT
 
volatile int16_t speed = 0
 
float targetSpeed = 0
 
int16_t targetPos = 0
 
int16_t maxEffort = 300
 
volatile int16_t prevCount = 0
 
volatile int16_t count = 0
 
volatile int16_t lastA = 0
 
volatile int16_t lastB = 0
 
PIDController pidCtrl
 

Friends

class Chassis
 

Detailed Description

Controls motor effort and direction on the Romi 32U4.

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

Also reads counts from the encoders on the Romi 32U4.

This class allows you to read counts from the encoders on the Romi 32U4, which lets you tell how much each motor has turned and in what direction.

The encoders are monitored in the background using interrupts, so your code can perform other tasks without missing encoder counts.

Definition at line 25 of file Romi32U4Motors.h.

Member Enumeration Documentation

◆ CTRL_MODE

enum Romi32U4Motor::CTRL_MODE : uint8_t
protected
Enumerator
CTRL_DIRECT 
CTRL_SPEED 
CTRL_POS 

Definition at line 29 of file Romi32U4Motors.h.

Constructor & Destructor Documentation

◆ Romi32U4Motor()

Romi32U4Motor::Romi32U4Motor ( void  )
inline

Definition at line 54 of file Romi32U4Motors.h.

Member Function Documentation

◆ allowTurbo()

void Romi32U4Motor::allowTurbo ( bool  turbo)

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.

Parameters
turboIf true, turns turbo mode on. If false, turns turbo mode off.

Top speed is limited to 300/420 by default. This allow you to go faster. Be careful.

Definition at line 101 of file Romi32U4Motors.cpp.

References maxEffort.

◆ calcEncoderDelta()

void Romi32U4Motor::calcEncoderDelta ( void  )
protected

calcEncoderDelta() is called automatically by an ISR. It takes a 'snapshot of the encoders and stores the change since the last call in speed, which has units of "encoder ticks/16 ms interval"

Because it is called from within an ISR, interrupts don't need to be disabled.

Definition at line 90 of file Romi32U4Encoders.cpp.

References count, prevCount, and speed.

Referenced by Chassis::updateEncoderDeltas().

◆ checkComplete()

bool Romi32U4Motor::checkComplete ( void  )
inlineprotected

Definition at line 98 of file Romi32U4Motors.h.

References CTRL_DIRECT, and ctrlMode.

Referenced by Chassis::checkMotionComplete().

◆ getAndResetCount()

int16_t Romi32U4Motor::getAndResetCount ( void  )
protected

Resets the encoder count and returns the last count.

Definition at line 75 of file Romi32U4Encoders.cpp.

References count.

Referenced by initEncoders().

◆ getCount()

int16_t Romi32U4Motor::getCount ( void  )
protected

Returns the number of counts that have been detected from the encoder. These counts start at 0. Positive counts correspond to forward movement of the left side of the Romi, while negative counts correspond to backwards movement.

The count is returned as a signed 16-bit integer. When the count goes over 32767, it will overflow down to -32768. When the count goes below -32768, it will underflow up to 32767.

Returns the current encoder count.

Definition at line 64 of file Romi32U4Encoders.cpp.

References count.

Referenced by Chassis::printEncoderCounts().

◆ handleISR()

void Romi32U4Motor::handleISR ( bool  newA,
bool  newB 
)
inline

Service function for the ISR

Calculates the encoder counter increment/decrement due to an encoder transition. Pololu sets up their encoders in an interesting way with some logic chips, so first we have to deconvolute the encoder signals (in the ISR); then, we call this function to update the counter.

More details are found here:

https://www.pololu.com/docs/0J69/3.3

This function is called from the ISR, which does the actual deconvolution for each motor.

Definition at line 108 of file Romi32U4Encoders.cpp.

References count, CTRL_DIRECT, CTRL_POS, ctrlMode, lastA, lastB, setEffort(), and targetPos.

Referenced by initEncoders(), leftISR(), and rightISR().

◆ init()

static void Romi32U4Motor::init ( void  )
inlinestatic

Must be called near the beginning of the program [usually in Chassis::init()]

Definition at line 59 of file Romi32U4Motors.h.

References initEncoders(), and initMotors().

Referenced by Chassis::init().

◆ initEncoders()

void Romi32U4Motor::initEncoders ( void  )
staticprotected

Set up the encoder 'machinery'. Call it near the beginning of the program.

Do not edit this function.

Definition at line 26 of file Romi32U4Encoders.cpp.

References attachPCInt(), chassis, getAndResetCount(), handleISR(), FastGPIO::Pin< pin >::isInputHigh(), leftISR(), Chassis::leftMotor, rightISR(), Chassis::rightMotor, and FastGPIO::Pin< pin >::setInputPulledUp().

Referenced by init().

◆ initMotors()

void Romi32U4Motor::initMotors ( )
staticprotected

initMotors() should be called near the beginning of the program (usually in Chassis::init()). It sets up Timer4 to run at 38 kHz, which is used to both drive the PWM signal for the motors and (tangentially) allow for a 38 kHz signal on pin 11, which can be used, say, to drive an IR LED at a common rate.

Timer 1 has the following configuration: prescaler of 1 outputs enabled on channels A (pin 9), B (pin 10) and C (pin 11) fast PWM mode top of 420, which will be the max speed frequency is then: 16 MHz / [1 (prescaler) / (420 + 1)] = 38.005 kHz

Definition at line 28 of file Romi32U4Motors.cpp.

References FastGPIO::Pin< pin >::setOutputLow().

Referenced by init().

◆ moveFor()

void Romi32U4Motor::moveFor ( int16_t  amount)
protected

Sets the (delta) target position in "encoder ticks" and a speed to drive to get there in "encoder ticks/16 ms interval"

Definition at line 139 of file Romi32U4Motors.cpp.

References count, CTRL_POS, ctrlMode, and targetPos.

Referenced by Chassis::driveFor(), and Chassis::turnFor().

◆ setEffort()

virtual void Romi32U4Motor::setEffort ( int16_t  effort)
protectedpure virtual

Sets the effort for the motor directly. Overloaded for the left and right motors. Use Chassis::setEfforts() from the user code to control motor efforts directly.

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

Implemented in LeftMotor, and RightMotor.

Referenced by handleISR(), and update().

◆ setPIDCoeffients()

void Romi32U4Motor::setPIDCoeffients ( float  kp,
float  ki 
)
inline

Definition at line 65 of file Romi32U4Motors.h.

References pidCtrl, PIDController::setKi(), and PIDController::setKp().

Referenced by Chassis::setMotorPIDcoeffs().

◆ setTargetSpeed()

void Romi32U4Motor::setTargetSpeed ( float  target)
protected

Sets the target speed in "encoder ticks/16 ms interval"

Definition at line 121 of file Romi32U4Motors.cpp.

References CTRL_SPEED, ctrlMode, pidCtrl, PIDController::resetSum(), and targetSpeed.

Referenced by Chassis::setTwist(), and Chassis::setWheelSpeeds().

◆ update()

void Romi32U4Motor::update ( void  )
protected

update() must be called regularly to update the control signals sent to the motors.

Definition at line 109 of file Romi32U4Motors.cpp.

References PIDController::calcEffort(), CTRL_POS, CTRL_SPEED, ctrlMode, pidCtrl, setEffort(), speed, and targetSpeed.

Referenced by Chassis::updateEncoderDeltas().

Friends And Related Function Documentation

◆ Chassis

friend class Chassis
friend

Definition at line 51 of file Romi32U4Motors.h.

Field Documentation

◆ count

volatile int16_t Romi32U4Motor::count = 0
protected

Definition at line 44 of file Romi32U4Motors.h.

Referenced by calcEncoderDelta(), getAndResetCount(), getCount(), handleISR(), and moveFor().

◆ ctrlMode

volatile CTRL_MODE Romi32U4Motor::ctrlMode = CTRL_DIRECT
protected

◆ lastA

volatile int16_t Romi32U4Motor::lastA = 0
protected

Definition at line 45 of file Romi32U4Motors.h.

Referenced by handleISR().

◆ lastB

volatile int16_t Romi32U4Motor::lastB = 0
protected

Definition at line 46 of file Romi32U4Motors.h.

Referenced by handleISR().

◆ maxEffort

int16_t Romi32U4Motor::maxEffort = 300
protected

Definition at line 40 of file Romi32U4Motors.h.

Referenced by allowTurbo(), LeftMotor::setEffort(), and RightMotor::setEffort().

◆ pidCtrl

PIDController Romi32U4Motor::pidCtrl
protected

Definition at line 49 of file Romi32U4Motors.h.

Referenced by setPIDCoeffients(), setTargetSpeed(), and update().

◆ prevCount

volatile int16_t Romi32U4Motor::prevCount = 0
protected

Definition at line 43 of file Romi32U4Motors.h.

Referenced by calcEncoderDelta().

◆ speed

volatile int16_t Romi32U4Motor::speed = 0
protected

Definition at line 33 of file Romi32U4Motors.h.

Referenced by calcEncoderDelta(), Chassis::printSpeeds(), and update().

◆ targetPos

int16_t Romi32U4Motor::targetPos = 0
protected

Definition at line 37 of file Romi32U4Motors.h.

Referenced by handleISR(), and moveFor().

◆ targetSpeed

float Romi32U4Motor::targetSpeed = 0
protected

Definition at line 36 of file Romi32U4Motors.h.

Referenced by setTargetSpeed(), and update().


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