-
Notifications
You must be signed in to change notification settings - Fork 12
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Added Romi32U4LCD and Romi32U4Motors.
- Loading branch information
1 parent
50a5b43
commit d34d59a
Showing
4 changed files
with
259 additions
and
1 deletion.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,82 @@ | ||
// Copyright Pololu Corporation. For more information, see http://www.pololu.com/ | ||
|
||
/*! \file Romi32U4LCD.h */ | ||
|
||
#pragma once | ||
|
||
#include <PololuHD44780.h> | ||
#include <FastGPIO.h> | ||
#include <USBPause.h> | ||
|
||
/*! \brief Writes data to the LCD on the Romi 32U4. | ||
* | ||
* This library is similar to the Arduino | ||
* [LiquidCrystal library](http://arduino.cc/en/Reference/LiquidCrystal), | ||
* but it has some extra features needed on the Romi 32U4: | ||
* | ||
* * This class disables USB interrupts temporarily while writing to the LCD so | ||
* that the USB interrupts will not change the RXLED and TXLED pins, which | ||
* double as LCD data lines. | ||
* * This class restores the RS, DB4, DB5, DB6, and DB7 pins to their previous | ||
* states when it is done using them so that those pins can also be used for | ||
* other purposes such as controlling LEDs. | ||
* | ||
* This class inherits from the Arduino Print class, so you can call the | ||
* `print()` function on it with a variety of arguments. See the | ||
* [Arduino print() documentation](http://arduino.cc/en/Serial/Print) | ||
* for more information. | ||
* | ||
* For detailed information about HD44780 LCD interface, including what | ||
* characters can be displayed, see the | ||
* [HD44780 datasheet](http://www.pololu.com/file/0J72/HD44780.pdf). | ||
*/ | ||
class Romi32U4LCD : public PololuHD44780Base | ||
{ | ||
// Pin assignments | ||
static const uint8_t rs = 4, e = 11, db4 = 14, db5 = 17, db6 = 13, db7 = IO_D5; | ||
|
||
public: | ||
|
||
virtual void initPins() | ||
{ | ||
FastGPIO::Pin<e>::setOutputLow(); | ||
} | ||
|
||
virtual void send(uint8_t data, bool rsValue, bool only4bits) | ||
{ | ||
// Temporarily disable USB interrupts because they write some pins | ||
// we are using as LCD pins. | ||
USBPause usbPause; | ||
|
||
// Save the state of the RS and data pins. The state automatically | ||
// gets restored before this function returns. | ||
FastGPIO::PinLoan<rs> loanRS; | ||
FastGPIO::PinLoan<db4> loanDB4; | ||
FastGPIO::PinLoan<db5> loanDB5; | ||
FastGPIO::PinLoan<db6> loanDB6; | ||
FastGPIO::PinLoan<db7> loanDB7; | ||
|
||
// Drive the RS pin high or low. | ||
FastGPIO::Pin<rs>::setOutput(rsValue); | ||
|
||
// Send the data. | ||
if (!only4bits) { sendNibble(data >> 4); } | ||
sendNibble(data & 0x0F); | ||
} | ||
|
||
private: | ||
|
||
void sendNibble(uint8_t data) | ||
{ | ||
FastGPIO::Pin<db4>::setOutput(data >> 0 & 1); | ||
FastGPIO::Pin<db5>::setOutput(data >> 1 & 1); | ||
FastGPIO::Pin<db6>::setOutput(data >> 2 & 1); | ||
FastGPIO::Pin<db7>::setOutput(data >> 3 & 1); | ||
|
||
FastGPIO::Pin<e>::setOutputHigh(); | ||
_delay_us(1); // Must be at least 450 ns. | ||
FastGPIO::Pin<e>::setOutputLow(); | ||
_delay_us(1); // Must be at least 550 ns. | ||
} | ||
}; | ||
|
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,99 @@ | ||
// Copyright Pololu Corporation. For more information, see http://www.pololu.com/ | ||
|
||
#include <Romi32U4Motors.h> | ||
#include <FastGPIO.h> | ||
#include <avr/io.h> | ||
|
||
#define PWM_L 10 | ||
#define PWM_R 9 | ||
#define DIR_L 16 | ||
#define DIR_R 15 | ||
|
||
static bool flipLeft = false; | ||
static bool flipRight = false; | ||
|
||
// initialize timer1 to generate the proper PWM outputs to the motor drivers | ||
void Romi32U4Motors::init2() | ||
{ | ||
FastGPIO::Pin<PWM_L>::setOutputLow(); | ||
FastGPIO::Pin<PWM_R>::setOutputLow(); | ||
FastGPIO::Pin<DIR_L>::setOutputLow(); | ||
FastGPIO::Pin<DIR_R>::setOutputLow(); | ||
|
||
// Timer 1 configuration | ||
// prescaler: clockI/O / 1 | ||
// outputs enabled | ||
// phase-correct PWM | ||
// top of 400 | ||
// | ||
// PWM frequency calculation | ||
// 16MHz / 1 (prescaler) / 2 (phase-correct) / 400 (top) = 20kHz | ||
TCCR1A = 0b10100000; | ||
TCCR1B = 0b00010001; | ||
ICR1 = 400; | ||
OCR1A = 0; | ||
OCR1B = 0; | ||
} | ||
|
||
// enable/disable flipping of left motor | ||
void Romi32U4Motors::flipLeftMotor(bool flip) | ||
{ | ||
flipLeft = flip; | ||
} | ||
|
||
// enable/disable flipping of right motor | ||
void Romi32U4Motors::flipRightMotor(bool flip) | ||
{ | ||
flipRight = flip; | ||
} | ||
|
||
// set speed for left motor; speed is a number between -400 and 400 | ||
void Romi32U4Motors::setLeftSpeed(int16_t speed) | ||
{ | ||
init(); | ||
|
||
bool reverse = 0; | ||
|
||
if (speed < 0) | ||
{ | ||
speed = -speed; // Make speed a positive quantity. | ||
reverse = 1; // Preserve the direction. | ||
} | ||
if (speed > 400) // Max PWM duty cycle. | ||
{ | ||
speed = 400; | ||
} | ||
|
||
OCR1B = speed; | ||
|
||
FastGPIO::Pin<DIR_L>::setOutput(reverse ^ flipLeft); | ||
} | ||
|
||
// set speed for right motor; speed is a number between -400 and 400 | ||
void Romi32U4Motors::setRightSpeed(int16_t speed) | ||
{ | ||
init(); | ||
|
||
bool reverse = 0; | ||
|
||
if (speed < 0) | ||
{ | ||
speed = -speed; // Make speed a positive quantity. | ||
reverse = 1; // Preserve the direction. | ||
} | ||
if (speed > 400) // Max PWM duty cycle. | ||
{ | ||
speed = 400; | ||
} | ||
|
||
OCR1A = speed; | ||
|
||
FastGPIO::Pin<DIR_R>::setOutput(reverse ^ flipRight); | ||
} | ||
|
||
// set speed for both motors | ||
void Romi32U4Motors::setSpeeds(int16_t leftSpeed, int16_t rightSpeed) | ||
{ | ||
setLeftSpeed(leftSpeed); | ||
setRightSpeed(rightSpeed); | ||
} |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,78 @@ | ||
// Copyright Pololu Corporation. For more information, see http://www.pololu.com/ | ||
|
||
/*! \file Romi32U4Motors.h */ | ||
|
||
#pragma once | ||
|
||
#include <stdint.h> | ||
|
||
/*! \brief 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. */ | ||
class Romi32U4Motors | ||
{ | ||
public: | ||
|
||
/** \brief Flips the direction of the left motor. | ||
* | ||
* You can call this function with an argument of \c 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. | ||
* | ||
* \param 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. | ||
*/ | ||
static void flipLeftMotor(bool flip); | ||
|
||
/** \brief Flips the direction of the right motor. | ||
* | ||
* You can call this function with an argument of \c 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. | ||
* | ||
* \param 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. */ | ||
static void flipRightMotor(bool flip); | ||
|
||
/** \brief Sets the speed for the left motor. | ||
* | ||
* \param speed A 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. */ | ||
static void setLeftSpeed(int16_t speed); | ||
|
||
/** \brief Sets the speed for the left motor. | ||
* | ||
* \param speed A 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. */ | ||
static void setRightSpeed(int16_t speed); | ||
|
||
/** \brief Sets the speed for the left motor. | ||
* | ||
* \param leftSpeed A 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. | ||
* \param rightSpeed A 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. */ | ||
static void setSpeeds(int16_t leftSpeed, int16_t rightSpeed); | ||
|
||
private: | ||
|
||
static inline void init() | ||
{ | ||
static bool initialized = false; | ||
|
||
if (!initialized) | ||
{ | ||
initialized = true; | ||
init2(); | ||
} | ||
} | ||
|
||
static void init2(); | ||
}; |