SubZero Common
Common library components for an FRC CommandRobot
Loading...
Searching...
No Matches
ConnectorX::ConnectorXBoard Class Reference

Driver for use with the I2C, V2 iteration of Connector-X. More...

#include <ConnectorX.h>

+ Inheritance diagram for ConnectorX::ConnectorXBoard:
+ Collaboration diagram for ConnectorX::ConnectorXBoard:

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.
 
CachedPortgetCurrentCachedPort ()
 
void setLedPort (LedPort port)
 
CachedZonesetCurrentZone (LedPort port, uint8_t zoneIndex=0, bool reversed=false, bool setReversed=false)
 Set the current zone for running patterns.
 
CachedZonegetCurrentZone ()
 
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.
 

Detailed Description

Driver for use with the I2C, V2 iteration of Connector-X.

Definition at line 320 of file ConnectorX.h.

Constructor & Destructor Documentation

◆ ConnectorXBoard()

ConnectorX::ConnectorXBoard::ConnectorXBoard ( uint8_t slaveAddress,
frc::I2C::Port port = frc::I2C::kMXP,
units::second_t connectorXDelay = 0.002_s )
explicit

Construct a new Connector-X driver instance.

Parameters
slaveAddressSet in the board's configuration
portWill typically be the 40-pin frc::I2C::kMXP header
connectorXDelayDelay in seconds between sending commands

Member Function Documentation

◆ configureDigitalPin()

void ConnectorX::ConnectorXBoard::configureDigitalPin ( DigitalPort port,
PinMode mode )

Configure a digital IO pin. Think Arduino pinMode()

Parameters
port
modeInput, Output, etc.

◆ createZones()

void ConnectorX::ConnectorXBoard::createZones ( LedPort port,
std::vector< Commands::NewZone > && newZones )

Create up to 10 new zones.

◆ getCurrentCachedPort()

CachedPort & ConnectorX::ConnectorXBoard::getCurrentCachedPort ( )
inline

Definition at line 486 of file ConnectorX.h.

◆ getCurrentColor()

frc::Color8Bit ConnectorX::ConnectorXBoard::getCurrentColor ( LedPort port,
uint8_t zoneIndex = 0 )
inline

Get the current on-board Color, not the cached one.

Definition at line 438 of file ConnectorX.h.

◆ getCurrentLedPort()

LedPort ConnectorX::ConnectorXBoard::getCurrentLedPort ( )
inline

Get the current port.

Returns
LedPort

Definition at line 482 of file ConnectorX.h.

◆ getCurrentZone()

CachedZone & ConnectorX::ConnectorXBoard::getCurrentZone ( )
inline

Definition at line 505 of file ConnectorX.h.

◆ getLatestRadioMessage()

Message ConnectorX::ConnectorXBoard::getLatestRadioMessage ( )

Read the last received message.

Returns
Message

◆ getPatternDone()

bool ConnectorX::ConnectorXBoard::getPatternDone ( LedPort port)

Read if pattern is done running.

Returns
true if pattern is done

◆ initialize()

bool ConnectorX::ConnectorXBoard::initialize ( )

Start communication with the controller.

Returns
true if successful init

◆ lastCommand()

Commands::CommandType ConnectorX::ConnectorXBoard::lastCommand ( ) const
inline

Get the last command sent.

Returns
CommandType

Definition at line 345 of file ConnectorX.h.

◆ lastPattern()

PatternType ConnectorX::ConnectorXBoard::lastPattern ( LedPort port,
uint8_t zoneIndex = 0 ) const
inline

Get the last pattern sent.

Parameters
port
Returns
PatternType

Definition at line 353 of file ConnectorX.h.

◆ readAnalogPin()

uint16_t ConnectorX::ConnectorXBoard::readAnalogPin ( AnalogPort port)

Read the ADC value. Ranges from 0 - 3.3v; 12 bits of precision.

Parameters
port
Returns
uint16_t

◆ readConfig()

Commands::Configuration ConnectorX::ConnectorXBoard::readConfig ( )

Read the config stored in EEPROM.

Returns
Configuration

◆ readDigitalPin()

bool ConnectorX::ConnectorXBoard::readDigitalPin ( DigitalPort port)

Read state of digital IO pin.

Parameters
port
Returns
true - Remember this will be HIGH by default if set to INPUT_PULLUP
false

◆ sendRadioMessage()

void ConnectorX::ConnectorXBoard::sendRadioMessage ( Message message)

Send a message via the radio; set team to 0xFFFF to broadcast to all.

Parameters
message

◆ setColor() [1/3]

void ConnectorX::ConnectorXBoard::setColor ( LedPort port,
frc::Color8Bit color,
uint8_t zoneIndex = 0 )
inline

Set the color using frc::Color8Bit.

Definition at line 421 of file ConnectorX.h.

◆ setColor() [2/3]

void ConnectorX::ConnectorXBoard::setColor ( LedPort port,
uint32_t color,
uint8_t zoneIndex = 0 )
inline

Set the color; must also call a pattern to see it.

Parameters
colorColor data in the form of 0x00RRGGBB

Definition at line 430 of file ConnectorX.h.

◆ setColor() [3/3]

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.

◆ setConfig()

void ConnectorX::ConnectorXBoard::setConfig ( Commands::Configuration config)

Store the config in board's EEPROM.

Parameters
config

◆ setCurrentZone()

CachedZone & ConnectorX::ConnectorXBoard::setCurrentZone ( LedPort port,
uint8_t zoneIndex = 0,
bool reversed = false,
bool setReversed = false )

Set the current zone for running patterns.

Parameters
port
zoneIndex
reversedRun the pattern in reverse
setReversedWill set the zone to reversed when true and reversed is true
Returns
CachedZone&

◆ setLedPort()

void ConnectorX::ConnectorXBoard::setLedPort ( LedPort port)

◆ setOff()

void ConnectorX::ConnectorXBoard::setOff ( )

Turn off.

◆ setOn()

void ConnectorX::ConnectorXBoard::setOn ( )

Turn on.

◆ setPattern()

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.

Parameters
pattern
oneShotOnly run the pattern once

◆ syncZones()

void ConnectorX::ConnectorXBoard::syncZones ( LedPort port,
const std::vector< uint8_t > & zones )

Sync up to 10 zones to the same 0 state.

◆ writeDigitalPin()

void ConnectorX::ConnectorXBoard::writeDigitalPin ( DigitalPort port,
bool value )

Set a digital IO pin.

Parameters
value

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