SubZero Common
Common library components for an FRC CommandRobot
|
Driver for use with the I2C, V2 iteration of Connector-X. More...
#include <ConnectorX.h>
Public Member Functions | |
ConnectorXBoard (uint8_t slaveAddress, frc::I2C::Port port=frc::I2C::kMXP, units::second_t connectorXDelay=0.002_s) | |
Construct a new Connector-X driver instance. | |
bool | initialize () |
Start communication with the controller. | |
Commands::CommandType | lastCommand () const |
Get the last command sent. | |
PatternType | lastPattern (LedPort port, uint8_t zoneIndex=0) const |
Get the last pattern sent. | |
void | configureDigitalPin (DigitalPort port, PinMode mode) |
Configure a digital IO pin. Think Arduino pinMode() | |
void | writeDigitalPin (DigitalPort port, bool value) |
Set a digital IO pin. | |
bool | readDigitalPin (DigitalPort port) |
Read state of digital IO pin. | |
uint16_t | readAnalogPin (AnalogPort port) |
Read the ADC value. Ranges from 0 - 3.3v; 12 bits of precision. | |
void | setOn () |
Turn on. | |
void | setOff () |
Turn off. | |
void | setPattern (LedPort port, PatternType pattern, bool oneShot=false, int16_t delay=-1, uint8_t zoneIndex=0, bool reversed=false) |
Send the PATTERN command. | |
void | setColor (LedPort port, uint8_t red, uint8_t green, uint8_t blue, uint8_t zoneIndex=0) |
Set the color; must also call a pattern to see it. | |
void | setColor (LedPort port, frc::Color8Bit color, uint8_t zoneIndex=0) |
Set the color using frc::Color8Bit. | |
void | setColor (LedPort port, uint32_t color, uint8_t zoneIndex=0) |
Set the color; must also call a pattern to see it. | |
frc::Color8Bit | getCurrentColor (LedPort port, uint8_t zoneIndex=0) |
Get the current on-board Color, not the cached one. | |
bool | getPatternDone (LedPort port) |
Read if pattern is done running. | |
void | setConfig (Commands::Configuration config) |
Store the config in board's EEPROM. | |
Commands::Configuration | readConfig () |
Read the config stored in EEPROM. | |
void | sendRadioMessage (Message message) |
Send a message via the radio; set team to 0xFFFF to broadcast to all. | |
Message | getLatestRadioMessage () |
Read the last received message. | |
LedPort | getCurrentLedPort () |
Get the current port. | |
CachedPort & | getCurrentCachedPort () |
void | setLedPort (LedPort port) |
CachedZone & | setCurrentZone (LedPort port, uint8_t zoneIndex=0, bool reversed=false, bool setReversed=false) |
Set the current zone for running patterns. | |
CachedZone & | getCurrentZone () |
void | syncZones (LedPort port, const std::vector< uint8_t > &zones) |
Sync up to 10 zones to the same 0 state. | |
void | createZones (LedPort port, std::vector< Commands::NewZone > &&newZones) |
Create up to 10 new zones. | |
Driver for use with the I2C, V2 iteration of Connector-X.
Definition at line 320 of file ConnectorX.h.
|
explicit |
Construct a new Connector-X driver instance.
slaveAddress | Set in the board's configuration |
port | Will typically be the 40-pin frc::I2C::kMXP header |
connectorXDelay | Delay in seconds between sending commands |
void ConnectorX::ConnectorXBoard::configureDigitalPin | ( | DigitalPort | port, |
PinMode | mode ) |
Configure a digital IO pin. Think Arduino pinMode()
port | |
mode | Input, Output, etc. |
void ConnectorX::ConnectorXBoard::createZones | ( | LedPort | port, |
std::vector< Commands::NewZone > && | newZones ) |
Create up to 10 new zones.
|
inline |
Definition at line 486 of file ConnectorX.h.
|
inline |
Get the current on-board Color, not the cached one.
Definition at line 438 of file ConnectorX.h.
|
inline |
|
inline |
Definition at line 505 of file ConnectorX.h.
Message ConnectorX::ConnectorXBoard::getLatestRadioMessage | ( | ) |
Read the last received message.
bool ConnectorX::ConnectorXBoard::getPatternDone | ( | LedPort | port | ) |
Read if pattern is done running.
bool ConnectorX::ConnectorXBoard::initialize | ( | ) |
Start communication with the controller.
|
inline |
|
inline |
Get the last pattern sent.
port |
Definition at line 353 of file ConnectorX.h.
uint16_t ConnectorX::ConnectorXBoard::readAnalogPin | ( | AnalogPort | port | ) |
Read the ADC value. Ranges from 0 - 3.3v; 12 bits of precision.
port |
Commands::Configuration ConnectorX::ConnectorXBoard::readConfig | ( | ) |
Read the config stored in EEPROM.
bool ConnectorX::ConnectorXBoard::readDigitalPin | ( | DigitalPort | port | ) |
Read state of digital IO pin.
port |
void ConnectorX::ConnectorXBoard::sendRadioMessage | ( | Message | message | ) |
Send a message via the radio; set team to 0xFFFF to broadcast to all.
message |
|
inline |
Set the color using frc::Color8Bit.
Definition at line 421 of file ConnectorX.h.
|
inline |
Set the color; must also call a pattern to see it.
color | Color data in the form of 0x00RRGGBB |
Definition at line 430 of file ConnectorX.h.
void ConnectorX::ConnectorXBoard::setColor | ( | LedPort | port, |
uint8_t | red, | ||
uint8_t | green, | ||
uint8_t | blue, | ||
uint8_t | zoneIndex = 0 ) |
Set the color; must also call a pattern to see it.
void ConnectorX::ConnectorXBoard::setConfig | ( | Commands::Configuration | config | ) |
Store the config in board's EEPROM.
config |
CachedZone & ConnectorX::ConnectorXBoard::setCurrentZone | ( | LedPort | port, |
uint8_t | zoneIndex = 0, | ||
bool | reversed = false, | ||
bool | setReversed = false ) |
Set the current zone for running patterns.
port | |
zoneIndex | |
reversed | Run the pattern in reverse |
setReversed | Will set the zone to reversed when true and reversed is true |
void ConnectorX::ConnectorXBoard::setLedPort | ( | LedPort | port | ) |
void ConnectorX::ConnectorXBoard::setOff | ( | ) |
Turn off.
void ConnectorX::ConnectorXBoard::setOn | ( | ) |
Turn on.
void ConnectorX::ConnectorXBoard::setPattern | ( | LedPort | port, |
PatternType | pattern, | ||
bool | oneShot = false, | ||
int16_t | delay = -1, | ||
uint8_t | zoneIndex = 0, | ||
bool | reversed = false ) |
Send the PATTERN command.
pattern | |
oneShot | Only run the pattern once |
void ConnectorX::ConnectorXBoard::syncZones | ( | LedPort | port, |
const std::vector< uint8_t > & | zones ) |
Sync up to 10 zones to the same 0 state.
void ConnectorX::ConnectorXBoard::writeDigitalPin | ( | DigitalPort | port, |
bool | value ) |
Set a digital IO pin.
value |