Moved C++ comments from source files to headers (#1111)

Also sorted functions in C++ sources to match order in related headers.
This commit is contained in:
Tyler Veness
2018-05-31 20:47:15 -07:00
committed by Peter Johnson
parent d9971a705a
commit 8c680a26f8
234 changed files with 9936 additions and 9309 deletions

View File

@@ -13,13 +13,6 @@
using namespace frc;
/**
* Constructs the ADXL345 Accelerometer over I2C.
*
* @param port The I2C port the accelerometer is attached to
* @param range The range (+ or -) that the accelerometer will measure
* @param deviceAddress The I2C address of the accelerometer (0x1D or 0x53)
*/
ADXL345_I2C::ADXL345_I2C(I2C::Port port, Range range, int deviceAddress)
: m_i2c(port, deviceAddress) {
// Turn on the measurements
@@ -43,12 +36,6 @@ double ADXL345_I2C::GetY() { return GetAcceleration(kAxis_Y); }
double ADXL345_I2C::GetZ() { return GetAcceleration(kAxis_Z); }
/**
* Get the acceleration of one axis in Gs.
*
* @param axis The axis to read from.
* @return Acceleration of the ADXL345 in Gs.
*/
double ADXL345_I2C::GetAcceleration(ADXL345_I2C::Axes axis) {
int16_t rawAccel = 0;
m_i2c.Read(kDataRegister + static_cast<int>(axis), sizeof(rawAccel),
@@ -56,12 +43,6 @@ double ADXL345_I2C::GetAcceleration(ADXL345_I2C::Axes axis) {
return rawAccel * kGsPerLSB;
}
/**
* Get the acceleration of all axes in Gs.
*
* @return An object containing the acceleration measured on each axis of the
* ADXL345 in Gs.
*/
ADXL345_I2C::AllAxes ADXL345_I2C::GetAccelerations() {
AllAxes data = AllAxes();
int16_t rawData[3];

View File

@@ -13,12 +13,6 @@
using namespace frc;
/**
* Constructor.
*
* @param port The SPI port the accelerometer is attached to
* @param range The range (+ or -) that the accelerometer will measure
*/
ADXL345_SPI::ADXL345_SPI(SPI::Port port, ADXL345_SPI::Range range)
: m_spi(port) {
m_spi.SetClockRate(500000);
@@ -56,12 +50,6 @@ double ADXL345_SPI::GetY() { return GetAcceleration(kAxis_Y); }
double ADXL345_SPI::GetZ() { return GetAcceleration(kAxis_Z); }
/**
* Get the acceleration of one axis in Gs.
*
* @param axis The axis to read from.
* @return Acceleration of the ADXL345 in Gs.
*/
double ADXL345_SPI::GetAcceleration(ADXL345_SPI::Axes axis) {
uint8_t buffer[3];
uint8_t command[3] = {0, 0, 0};
@@ -74,12 +62,6 @@ double ADXL345_SPI::GetAcceleration(ADXL345_SPI::Axes axis) {
return rawAccel * kGsPerLSB;
}
/**
* Get the acceleration of all axes in Gs.
*
* @return An object containing the acceleration measured on each axis of the
* ADXL345 in Gs.
*/
ADXL345_SPI::AllAxes ADXL345_SPI::GetAccelerations() {
AllAxes data = AllAxes();
uint8_t dataBuffer[7] = {0, 0, 0, 0, 0, 0, 0};

View File

@@ -31,19 +31,8 @@ static constexpr int kPowerCtl_UltraLowNoise = 0x20;
// static constexpr int kPowerCtl_AutoSleep = 0x04;
static constexpr int kPowerCtl_Measure = 0x02;
/**
* Constructor. Uses the onboard CS1.
*
* @param range The range (+ or -) that the accelerometer will measure.
*/
ADXL362::ADXL362(Range range) : ADXL362(SPI::Port::kOnboardCS1, range) {}
/**
* Constructor.
*
* @param port The SPI port the accelerometer is attached to
* @param range The range (+ or -) that the accelerometer will measure.
*/
ADXL362::ADXL362(SPI::Port port, Range range) : m_spi(port) {
m_spi.SetClockRate(3000000);
m_spi.SetMSBFirst();
@@ -108,12 +97,6 @@ double ADXL362::GetY() { return GetAcceleration(kAxis_Y); }
double ADXL362::GetZ() { return GetAcceleration(kAxis_Z); }
/**
* Get the acceleration of one axis in Gs.
*
* @param axis The axis to read from.
* @return Acceleration of the ADXL362 in Gs.
*/
double ADXL362::GetAcceleration(ADXL362::Axes axis) {
if (m_gsPerLSB == 0.0) return 0.0;
@@ -128,12 +111,6 @@ double ADXL362::GetAcceleration(ADXL362::Axes axis) {
return rawAccel * m_gsPerLSB;
}
/**
* Get the acceleration of all axes in Gs.
*
* @return An object containing the acceleration measured on each axis of the
* ADXL362 in Gs.
*/
ADXL362::AllAxes ADXL362::GetAccelerations() {
AllAxes data = AllAxes();
if (m_gsPerLSB == 0.0) {

View File

@@ -28,39 +28,8 @@ static constexpr int kPIDRegister = 0x0C;
static constexpr int kSNHighRegister = 0x0E;
static constexpr int kSNLowRegister = 0x10;
/**
* Initialize the gyro.
*
* Calibrate the gyro by running for a number of samples and computing the
* center value. Then use the center value as the Accumulator center value for
* subsequent measurements.
*
* It's important to make sure that the robot is not moving while the centering
* calculations are in progress, this is typically done when the robot is first
* turned on while it's sitting at rest before the competition starts.
*/
void ADXRS450_Gyro::Calibrate() {
Wait(0.1);
m_spi.SetAccumulatorCenter(0);
m_spi.ResetAccumulator();
Wait(kCalibrationSampleTime);
m_spi.SetAccumulatorCenter(static_cast<int>(m_spi.GetAccumulatorAverage()));
m_spi.ResetAccumulator();
}
/**
* Gyro constructor on onboard CS0.
*/
ADXRS450_Gyro::ADXRS450_Gyro() : ADXRS450_Gyro(SPI::kOnboardCS0) {}
/**
* Gyro constructor on the specified SPI port.
*
* @param port The SPI port the gyro is attached to.
*/
ADXRS450_Gyro::ADXRS450_Gyro(SPI::Port port) : m_spi(port) {
m_spi.SetClockRate(3000000);
m_spi.SetMSBFirst();
@@ -116,39 +85,25 @@ uint16_t ADXRS450_Gyro::ReadRegister(int reg) {
return static_cast<uint16_t>((BytesToIntBE(buf) >> 5) & 0xffff);
}
/**
* Reset the gyro.
*
* Resets the gyro to a heading of zero. This can be used if there is
* significant drift in the gyro and it needs to be recalibrated after it has
* been running.
*/
void ADXRS450_Gyro::Reset() { m_spi.ResetAccumulator(); }
/**
* Return the actual angle in degrees that the robot is currently facing.
*
* The angle is based on the current accumulator value corrected by the
* oversampling rate, the gyro type and the A/D calibration values.
* The angle is continuous, that is it will continue from 360->361 degrees. This
* allows algorithms that wouldn't want to see a discontinuity in the gyro
* output as it sweeps from 360 to 0 on the second time around.
*
* @return the current heading of the robot in degrees. This heading is based on
* integration of the returned rate from the gyro.
*/
double ADXRS450_Gyro::GetAngle() const {
return m_spi.GetAccumulatorValue() * kDegreePerSecondPerLSB * kSamplePeriod;
}
/**
* Return the rate of rotation of the gyro
*
* The rate is based on the most recent reading of the gyro analog value
*
* @return the current rate in degrees per second
*/
double ADXRS450_Gyro::GetRate() const {
return static_cast<double>(m_spi.GetAccumulatorLastValue()) *
kDegreePerSecondPerLSB;
}
void ADXRS450_Gyro::Reset() { m_spi.ResetAccumulator(); }
void ADXRS450_Gyro::Calibrate() {
Wait(0.1);
m_spi.SetAccumulatorCenter(0);
m_spi.ResetAccumulator();
Wait(kCalibrationSampleTime);
m_spi.SetAccumulatorCenter(static_cast<int>(m_spi.GetAccumulatorAverage()));
m_spi.ResetAccumulator();
}

View File

@@ -14,38 +14,11 @@
using namespace frc;
/**
* Common function for initializing the accelerometer.
*/
void AnalogAccelerometer::InitAccelerometer() {
HAL_Report(HALUsageReporting::kResourceType_Accelerometer,
m_analogInput->GetChannel());
SetName("Accelerometer", m_analogInput->GetChannel());
}
/**
* Create a new instance of an accelerometer.
*
* The constructor allocates desired analog input.
*
* @param channel The channel number for the analog input the accelerometer is
* connected to
*/
AnalogAccelerometer::AnalogAccelerometer(int channel)
: AnalogAccelerometer(std::make_shared<AnalogInput>(channel)) {
AddChild(m_analogInput);
}
/**
* Create a new instance of Accelerometer from an existing AnalogInput.
*
* Make a new instance of accelerometer given an AnalogInput. This is
* particularly useful if the port is going to be read as an analog channel as
* well as through the Accelerometer class.
*
* @param channel The existing AnalogInput object for the analog input the
* accelerometer is connected to
*/
AnalogAccelerometer::AnalogAccelerometer(AnalogInput* channel)
: m_analogInput(channel, NullDeleter<AnalogInput>()) {
if (channel == nullptr) {
@@ -55,16 +28,6 @@ AnalogAccelerometer::AnalogAccelerometer(AnalogInput* channel)
}
}
/**
* Create a new instance of Accelerometer from an existing AnalogInput.
*
* Make a new instance of accelerometer given an AnalogInput. This is
* particularly useful if the port is going to be read as an analog channel as
* well as through the Accelerometer class.
*
* @param channel The existing AnalogInput object for the analog input the
* accelerometer is connected to
*/
AnalogAccelerometer::AnalogAccelerometer(std::shared_ptr<AnalogInput> channel)
: m_analogInput(channel) {
if (channel == nullptr) {
@@ -74,45 +37,16 @@ AnalogAccelerometer::AnalogAccelerometer(std::shared_ptr<AnalogInput> channel)
}
}
/**
* Return the acceleration in Gs.
*
* The acceleration is returned units of Gs.
*
* @return The current acceleration of the sensor in Gs.
*/
double AnalogAccelerometer::GetAcceleration() const {
return (m_analogInput->GetAverageVoltage() - m_zeroGVoltage) / m_voltsPerG;
}
/**
* Set the accelerometer sensitivity.
*
* This sets the sensitivity of the accelerometer used for calculating the
* acceleration. The sensitivity varies by accelerometer model. There are
* constants defined for various models.
*
* @param sensitivity The sensitivity of accelerometer in Volts per G.
*/
void AnalogAccelerometer::SetSensitivity(double sensitivity) {
m_voltsPerG = sensitivity;
}
/**
* Set the voltage that corresponds to 0 G.
*
* The zero G voltage varies by accelerometer model. There are constants defined
* for various models.
*
* @param zero The zero G voltage.
*/
void AnalogAccelerometer::SetZero(double zero) { m_zeroGVoltage = zero; }
/**
* Get the Acceleration for the PID Source parent.
*
* @return The current acceleration in Gs.
*/
double AnalogAccelerometer::PIDGet() { return GetAcceleration(); }
void AnalogAccelerometer::InitSendable(SendableBuilder& builder) {
@@ -120,3 +54,9 @@ void AnalogAccelerometer::InitSendable(SendableBuilder& builder) {
builder.AddDoubleProperty("Value", [=]() { return GetAcceleration(); },
nullptr);
}
void AnalogAccelerometer::InitAccelerometer() {
HAL_Report(HALUsageReporting::kResourceType_Accelerometer,
m_analogInput->GetChannel());
SetName("Accelerometer", m_analogInput->GetChannel());
}

View File

@@ -19,43 +19,15 @@
using namespace frc;
/**
* Gyro constructor using the Analog Input channel number.
*
* @param channel The analog channel the gyro is connected to. Gyros can only
* be used on on-board Analog Inputs 0-1.
*/
AnalogGyro::AnalogGyro(int channel)
: AnalogGyro(std::make_shared<AnalogInput>(channel)) {
AddChild(m_analog);
}
/**
* Gyro constructor with a precreated AnalogInput object.
*
* Use this constructor when the analog channel needs to be shared.
* This object will not clean up the AnalogInput object when using this
* constructor.
*
* Gyros can only be used on on-board channels 0-1.
*
* @param channel A pointer to the AnalogInput object that the gyro is
* connected to.
*/
AnalogGyro::AnalogGyro(AnalogInput* channel)
: AnalogGyro(
std::shared_ptr<AnalogInput>(channel, NullDeleter<AnalogInput>())) {}
/**
* Gyro constructor with a precreated AnalogInput object.
*
* Use this constructor when the analog channel needs to be shared.
* This object will not clean up the AnalogInput object when using this
* constructor.
*
* @param channel A pointer to the AnalogInput object that the gyro is
* connected to.
*/
AnalogGyro::AnalogGyro(std::shared_ptr<AnalogInput> channel)
: m_analog(channel) {
if (channel == nullptr) {
@@ -66,32 +38,11 @@ AnalogGyro::AnalogGyro(std::shared_ptr<AnalogInput> channel)
}
}
/**
* Gyro constructor using the Analog Input channel number with parameters for
* presetting the center and offset values. Bypasses calibration.
*
* @param channel The analog channel the gyro is connected to. Gyros can only
* be used on on-board Analog Inputs 0-1.
* @param center Preset uncalibrated value to use as the accumulator center
* value.
* @param offset Preset uncalibrated value to use as the gyro offset.
*/
AnalogGyro::AnalogGyro(int channel, int center, double offset)
: AnalogGyro(std::make_shared<AnalogInput>(channel), center, offset) {
AddChild(m_analog);
}
/**
* Gyro constructor with a precreated AnalogInput object and calibrated
* parameters.
*
* Use this constructor when the analog channel needs to be shared.
* This object will not clean up the AnalogInput object when using this
* constructor.
*
* @param channel A pointer to the AnalogInput object that the gyro is
* connected to.
*/
AnalogGyro::AnalogGyro(std::shared_ptr<AnalogInput> channel, int center,
double offset)
: m_analog(channel) {
@@ -111,19 +62,54 @@ AnalogGyro::AnalogGyro(std::shared_ptr<AnalogInput> channel, int center,
}
}
/**
* AnalogGyro Destructor
*
*/
AnalogGyro::~AnalogGyro() { HAL_FreeAnalogGyro(m_gyroHandle); }
/**
* Reset the gyro.
*
* Resets the gyro to a heading of zero. This can be used if there is
* significant drift in the gyro and it needs to be recalibrated after it has
* been running.
*/
double AnalogGyro::GetAngle() const {
if (StatusIsFatal()) return 0.0;
int32_t status = 0;
double value = HAL_GetAnalogGyroAngle(m_gyroHandle, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
return value;
}
double AnalogGyro::GetRate() const {
if (StatusIsFatal()) return 0.0;
int32_t status = 0;
double value = HAL_GetAnalogGyroRate(m_gyroHandle, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
return value;
}
int AnalogGyro::GetCenter() const {
if (StatusIsFatal()) return 0;
int32_t status = 0;
int value = HAL_GetAnalogGyroCenter(m_gyroHandle, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
return value;
}
double AnalogGyro::GetOffset() const {
if (StatusIsFatal()) return 0.0;
int32_t status = 0;
double value = HAL_GetAnalogGyroOffset(m_gyroHandle, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
return value;
}
void AnalogGyro::SetSensitivity(double voltsPerDegreePerSecond) {
int32_t status = 0;
HAL_SetAnalogGyroVoltsPerDegreePerSecond(m_gyroHandle,
voltsPerDegreePerSecond, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
void AnalogGyro::SetDeadband(double volts) {
if (StatusIsFatal()) return;
int32_t status = 0;
HAL_SetAnalogGyroDeadband(m_gyroHandle, volts, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
void AnalogGyro::Reset() {
if (StatusIsFatal()) return;
int32_t status = 0;
@@ -131,9 +117,6 @@ void AnalogGyro::Reset() {
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Initialize the gyro. Calibration is handled by Calibrate().
*/
void AnalogGyro::InitGyro() {
if (StatusIsFatal()) return;
if (m_gyroHandle == HAL_kInvalidHandle) {
@@ -173,98 +156,3 @@ void AnalogGyro::Calibrate() {
HAL_CalibrateAnalogGyro(m_gyroHandle, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Return the actual angle in degrees that the robot is currently facing.
*
* The angle is based on the current accumulator value corrected by the
* oversampling rate, the gyro type and the A/D calibration values.
* The angle is continuous, that is it will continue from 360->361 degrees. This
* allows algorithms that wouldn't want to see a discontinuity in the gyro
* output as it sweeps from 360 to 0 on the second time around.
*
* @return the current heading of the robot in degrees. This heading is based on
* integration of the returned rate from the gyro.
*/
double AnalogGyro::GetAngle() const {
if (StatusIsFatal()) return 0.0;
int32_t status = 0;
double value = HAL_GetAnalogGyroAngle(m_gyroHandle, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
return value;
}
/**
* Return the rate of rotation of the gyro
*
* The rate is based on the most recent reading of the gyro analog value
*
* @return the current rate in degrees per second
*/
double AnalogGyro::GetRate() const {
if (StatusIsFatal()) return 0.0;
int32_t status = 0;
double value = HAL_GetAnalogGyroRate(m_gyroHandle, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
return value;
}
/**
* Return the gyro offset value. If run after calibration,
* the offset value can be used as a preset later.
*
* @return the current offset value
*/
double AnalogGyro::GetOffset() const {
if (StatusIsFatal()) return 0.0;
int32_t status = 0;
double value = HAL_GetAnalogGyroOffset(m_gyroHandle, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
return value;
}
/**
* Return the gyro center value. If run after calibration,
* the center value can be used as a preset later.
*
* @return the current center value
*/
int AnalogGyro::GetCenter() const {
if (StatusIsFatal()) return 0;
int32_t status = 0;
int value = HAL_GetAnalogGyroCenter(m_gyroHandle, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
return value;
}
/**
* Set the gyro sensitivity.
*
* This takes the number of volts/degree/second sensitivity of the gyro and uses
* it in subsequent calculations to allow the code to work with multiple gyros.
* This value is typically found in the gyro datasheet.
*
* @param voltsPerDegreePerSecond The sensitivity in Volts/degree/second
*/
void AnalogGyro::SetSensitivity(double voltsPerDegreePerSecond) {
int32_t status = 0;
HAL_SetAnalogGyroVoltsPerDegreePerSecond(m_gyroHandle,
voltsPerDegreePerSecond, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Set the size of the neutral zone.
*
* Any voltage from the gyro less than this amount from the center is
* considered stationary. Setting a deadband will decrease the amount of drift
* when the gyro isn't rotating, but will make it less accurate.
*
* @param volts The size of the deadband in volts
*/
void AnalogGyro::SetDeadband(double volts) {
if (StatusIsFatal()) return;
int32_t status = 0;
HAL_SetAnalogGyroDeadband(m_gyroHandle, volts, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}

View File

@@ -19,12 +19,6 @@
using namespace frc;
/**
* Construct an analog input.
*
* @param channel The channel number on the roboRIO to represent. 0-3 are
* on-board 4-7 are on the MXP port.
*/
AnalogInput::AnalogInput(int channel) {
if (!SensorUtil::CheckAnalogInputChannel(channel)) {
wpi_setWPIErrorWithContext(ChannelIndexOutOfRange,
@@ -49,23 +43,11 @@ AnalogInput::AnalogInput(int channel) {
SetName("AnalogInput", channel);
}
/**
* Channel destructor.
*/
AnalogInput::~AnalogInput() {
HAL_FreeAnalogInputPort(m_port);
m_port = HAL_kInvalidHandle;
}
/**
* Get a sample straight from this channel.
*
* The sample is a 12-bit value representing the 0V to 5V range of the A/D
* converter in the module. The units are in A/D converter codes. Use
* GetVoltage() to get the analog value in calibrated units.
*
* @return A sample straight from this channel.
*/
int AnalogInput::GetValue() const {
if (StatusIsFatal()) return 0;
int32_t status = 0;
@@ -74,20 +56,6 @@ int AnalogInput::GetValue() const {
return value;
}
/**
* Get a sample from the output of the oversample and average engine for this
* channel.
*
* The sample is 12-bit + the bits configured in SetOversampleBits().
* The value configured in SetAverageBits() will cause this value to be averaged
* 2**bits number of samples.
* This is not a sliding window. The sample will not change until
* 2**(OversampleBits + AverageBits) samples
* have been acquired from the module on this channel.
* Use GetAverageVoltage() to get the analog value in calibrated units.
*
* @return A sample from the oversample and average engine for this channel.
*/
int AnalogInput::GetAverageValue() const {
if (StatusIsFatal()) return 0;
int32_t status = 0;
@@ -96,14 +64,6 @@ int AnalogInput::GetAverageValue() const {
return value;
}
/**
* Get a scaled sample straight from this channel.
*
* The value is scaled to units of Volts using the calibrated scaling data from
* GetLSBWeight() and GetOffset().
*
* @return A scaled sample straight from this channel.
*/
double AnalogInput::GetVoltage() const {
if (StatusIsFatal()) return 0.0;
int32_t status = 0;
@@ -112,20 +72,6 @@ double AnalogInput::GetVoltage() const {
return voltage;
}
/**
* Get a scaled sample from the output of the oversample and average engine for
* this channel.
*
* The value is scaled to units of Volts using the calibrated scaling data from
* GetLSBWeight() and GetOffset().
* Using oversampling will cause this value to be higher resolution, but it will
* update more slowly.
* Using averaging will cause this value to be more stable, but it will update
* more slowly.
*
* @return A scaled sample from the output of the oversample and average engine
* for this channel.
*/
double AnalogInput::GetAverageVoltage() const {
if (StatusIsFatal()) return 0.0;
int32_t status = 0;
@@ -134,57 +80,11 @@ double AnalogInput::GetAverageVoltage() const {
return voltage;
}
/**
* Get the factory scaling least significant bit weight constant.
*
* Volts = ((LSB_Weight * 1e-9) * raw) - (Offset * 1e-9)
*
* @return Least significant bit weight.
*/
int AnalogInput::GetLSBWeight() const {
if (StatusIsFatal()) return 0;
int32_t status = 0;
int lsbWeight = HAL_GetAnalogLSBWeight(m_port, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
return lsbWeight;
}
/**
* Get the factory scaling offset constant.
*
* Volts = ((LSB_Weight * 1e-9) * raw) - (Offset * 1e-9)
*
* @return Offset constant.
*/
int AnalogInput::GetOffset() const {
if (StatusIsFatal()) return 0;
int32_t status = 0;
int offset = HAL_GetAnalogOffset(m_port, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
return offset;
}
/**
* Get the channel number.
*
* @return The channel number.
*/
int AnalogInput::GetChannel() const {
if (StatusIsFatal()) return 0;
return m_channel;
}
/**
* Set the number of averaging bits.
*
* This sets the number of averaging bits. The actual number of averaged samples
* is 2^bits.
* Use averaging to improve the stability of your measurement at the expense of
* sampling rate.
* The averaging is done automatically in the FPGA.
*
* @param bits Number of bits of averaging.
*/
void AnalogInput::SetAverageBits(int bits) {
if (StatusIsFatal()) return;
int32_t status = 0;
@@ -192,14 +92,6 @@ void AnalogInput::SetAverageBits(int bits) {
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Get the number of averaging bits previously configured.
*
* This gets the number of averaging bits from the FPGA. The actual number of
* averaged samples is 2^bits. The averaging is done automatically in the FPGA.
*
* @return Number of bits of averaging previously configured.
*/
int AnalogInput::GetAverageBits() const {
int32_t status = 0;
int averageBits = HAL_GetAnalogAverageBits(m_port, &status);
@@ -207,16 +99,6 @@ int AnalogInput::GetAverageBits() const {
return averageBits;
}
/**
* Set the number of oversample bits.
*
* This sets the number of oversample bits. The actual number of oversampled
* values is 2^bits. Use oversampling to improve the resolution of your
* measurements at the expense of sampling rate. The oversampling is done
* automatically in the FPGA.
*
* @param bits Number of bits of oversampling.
*/
void AnalogInput::SetOversampleBits(int bits) {
if (StatusIsFatal()) return;
int32_t status = 0;
@@ -224,15 +106,6 @@ void AnalogInput::SetOversampleBits(int bits) {
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Get the number of oversample bits previously configured.
*
* This gets the number of oversample bits from the FPGA. The actual number of
* oversampled values is 2^bits. The oversampling is done automatically in the
* FPGA.
*
* @return Number of bits of oversampling previously configured.
*/
int AnalogInput::GetOversampleBits() const {
if (StatusIsFatal()) return 0;
int32_t status = 0;
@@ -241,11 +114,22 @@ int AnalogInput::GetOversampleBits() const {
return oversampleBits;
}
/**
* Is the channel attached to an accumulator.
*
* @return The analog input is attached to an accumulator.
*/
int AnalogInput::GetLSBWeight() const {
if (StatusIsFatal()) return 0;
int32_t status = 0;
int lsbWeight = HAL_GetAnalogLSBWeight(m_port, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
return lsbWeight;
}
int AnalogInput::GetOffset() const {
if (StatusIsFatal()) return 0;
int32_t status = 0;
int offset = HAL_GetAnalogOffset(m_port, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
return offset;
}
bool AnalogInput::IsAccumulatorChannel() const {
if (StatusIsFatal()) return false;
int32_t status = 0;
@@ -254,9 +138,6 @@ bool AnalogInput::IsAccumulatorChannel() const {
return isAccum;
}
/**
* Initialize the accumulator.
*/
void AnalogInput::InitAccumulator() {
if (StatusIsFatal()) return;
m_accumulatorOffset = 0;
@@ -265,22 +146,11 @@ void AnalogInput::InitAccumulator() {
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Set an initial value for the accumulator.
*
* This will be added to all values returned to the user.
*
* @param initialValue The value that the accumulator should start from when
* reset.
*/
void AnalogInput::SetAccumulatorInitialValue(int64_t initialValue) {
if (StatusIsFatal()) return;
m_accumulatorOffset = initialValue;
}
/**
* Resets the accumulator to the initial value.
*/
void AnalogInput::ResetAccumulator() {
if (StatusIsFatal()) return;
int32_t status = 0;
@@ -297,17 +167,6 @@ void AnalogInput::ResetAccumulator() {
}
}
/**
* Set the center value of the accumulator.
*
* The center value is subtracted from each A/D value before it is added to the
* accumulator. This is used for the center value of devices like gyros and
* accelerometers to take the device offset into account when integrating.
*
* This center value is based on the output of the oversampled and averaged
* source from the accumulator channel. Because of this, any non-zero
* oversample bits will affect the size of the value for this field.
*/
void AnalogInput::SetAccumulatorCenter(int center) {
if (StatusIsFatal()) return;
int32_t status = 0;
@@ -315,9 +174,6 @@ void AnalogInput::SetAccumulatorCenter(int center) {
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Set the accumulator's deadband.
*/
void AnalogInput::SetAccumulatorDeadband(int deadband) {
if (StatusIsFatal()) return;
int32_t status = 0;
@@ -325,14 +181,6 @@ void AnalogInput::SetAccumulatorDeadband(int deadband) {
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Read the accumulated value.
*
* Read the value that has been accumulating.
* The accumulator is attached after the oversample and average engine.
*
* @return The 64-bit value accumulated since the last Reset().
*/
int64_t AnalogInput::GetAccumulatorValue() const {
if (StatusIsFatal()) return 0;
int32_t status = 0;
@@ -341,14 +189,6 @@ int64_t AnalogInput::GetAccumulatorValue() const {
return value + m_accumulatorOffset;
}
/**
* Read the number of accumulated values.
*
* Read the count of the accumulated values since the accumulator was last
* Reset().
*
* @return The number of times samples from the channel were accumulated.
*/
int64_t AnalogInput::GetAccumulatorCount() const {
if (StatusIsFatal()) return 0;
int32_t status = 0;
@@ -357,15 +197,6 @@ int64_t AnalogInput::GetAccumulatorCount() const {
return count;
}
/**
* Read the accumulated value and the number of accumulated values atomically.
*
* This function reads the value and count from the FPGA atomically.
* This can be used for averaging.
*
* @param value Reference to the 64-bit accumulated output.
* @param count Reference to the number of accumulation cycles.
*/
void AnalogInput::GetAccumulatorOutput(int64_t& value, int64_t& count) const {
if (StatusIsFatal()) return;
int32_t status = 0;
@@ -374,25 +205,12 @@ void AnalogInput::GetAccumulatorOutput(int64_t& value, int64_t& count) const {
value += m_accumulatorOffset;
}
/**
* Set the sample rate per channel for all analog channels.
*
* The maximum rate is 500kS/s divided by the number of channels in use.
* This is 62500 samples/s per channel.
*
* @param samplesPerSecond The number of samples per second.
*/
void AnalogInput::SetSampleRate(double samplesPerSecond) {
int32_t status = 0;
HAL_SetAnalogSampleRate(samplesPerSecond, &status);
wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Get the current sample rate for all channels
*
* @return Sample rate.
*/
double AnalogInput::GetSampleRate() {
int32_t status = 0;
double sampleRate = HAL_GetAnalogSampleRate(&status);
@@ -400,11 +218,6 @@ double AnalogInput::GetSampleRate() {
return sampleRate;
}
/**
* Get the Average value for the PID Source base object.
*
* @return The average voltage.
*/
double AnalogInput::PIDGet() {
if (StatusIsFatal()) return 0.0;
return GetAverageVoltage();

View File

@@ -18,13 +18,6 @@
using namespace frc;
/**
* Construct an analog output on the given channel.
*
* All analog outputs are located on the MXP port.
*
* @param channel The channel number on the roboRIO to represent.
*/
AnalogOutput::AnalogOutput(int channel) {
if (!SensorUtil::CheckAnalogOutputChannel(channel)) {
wpi_setWPIErrorWithContext(ChannelIndexOutOfRange,
@@ -51,23 +44,8 @@ AnalogOutput::AnalogOutput(int channel) {
SetName("AnalogOutput", m_channel);
}
/**
* Destructor.
*
* Frees analog output resource.
*/
AnalogOutput::~AnalogOutput() { HAL_FreeAnalogOutputPort(m_port); }
/**
* Get the channel of this AnalogOutput.
*/
int AnalogOutput::GetChannel() { return m_channel; }
/**
* Set the value of the analog output.
*
* @param voltage The output value in Volts, from 0.0 to +5.0
*/
void AnalogOutput::SetVoltage(double voltage) {
int32_t status = 0;
HAL_SetAnalogOutput(m_port, voltage, &status);
@@ -75,11 +53,6 @@ void AnalogOutput::SetVoltage(double voltage) {
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Get the voltage of the analog output
*
* @return The value in Volts, from 0.0 to +5.0
*/
double AnalogOutput::GetVoltage() const {
int32_t status = 0;
double voltage = HAL_GetAnalogOutput(m_port, &status);
@@ -89,6 +62,8 @@ double AnalogOutput::GetVoltage() const {
return voltage;
}
int AnalogOutput::GetChannel() { return m_channel; }
void AnalogOutput::InitSendable(SendableBuilder& builder) {
builder.SetSmartDashboardType("Analog Output");
builder.AddDoubleProperty("Value", [=]() { return GetVoltage(); },

View File

@@ -12,16 +12,6 @@
using namespace frc;
/**
* Construct an Analog Potentiometer object from a channel number.
*
* @param channel The channel number on the roboRIO to represent. 0-3 are
* on-board 4-7 are on the MXP port.
* @param fullRange The angular value (in desired units) representing the full
* 0-5V range of the input.
* @param offset The angular value (in desired units) representing the
* angular output at 0V.
*/
AnalogPotentiometer::AnalogPotentiometer(int channel, double fullRange,
double offset)
: m_analog_input(std::make_shared<AnalogInput>(channel)),
@@ -30,58 +20,24 @@ AnalogPotentiometer::AnalogPotentiometer(int channel, double fullRange,
AddChild(m_analog_input);
}
/**
* Construct an Analog Potentiometer object from an existing Analog Input
* pointer.
*
* @param channel The existing Analog Input pointer
* @param fullRange The angular value (in desired units) representing the full
* 0-5V range of the input.
* @param offset The angular value (in desired units) representing the
* angular output at 0V.
*/
AnalogPotentiometer::AnalogPotentiometer(AnalogInput* input, double fullRange,
double offset)
: m_analog_input(input, NullDeleter<AnalogInput>()),
m_fullRange(fullRange),
m_offset(offset) {}
/**
* Construct an Analog Potentiometer object from an existing Analog Input
* pointer.
*
* @param channel The existing Analog Input pointer
* @param fullRange The angular value (in desired units) representing the full
* 0-5V range of the input.
* @param offset The angular value (in desired units) representing the
* angular output at 0V.
*/
AnalogPotentiometer::AnalogPotentiometer(std::shared_ptr<AnalogInput> input,
double fullRange, double offset)
: m_analog_input(input), m_fullRange(fullRange), m_offset(offset) {}
/**
* Get the current reading of the potentiometer.
*
* @return The current position of the potentiometer (in the units used for
* fullRange and offset).
*/
double AnalogPotentiometer::Get() const {
return (m_analog_input->GetVoltage() / RobotController::GetVoltage5V()) *
m_fullRange +
m_offset;
}
/**
* Implement the PIDSource interface.
*
* @return The current reading.
*/
double AnalogPotentiometer::PIDGet() { return Get(); }
/**
* Live Window code, only does anything if live window is activated.
*/
void AnalogPotentiometer::InitSendable(SendableBuilder& builder) {
m_analog_input->InitSendable(builder);
}

View File

@@ -16,26 +16,12 @@
using namespace frc;
/**
* Constructor for an analog trigger given a channel number.
*
* @param channel The channel number on the roboRIO to represent. 0-3 are
* on-board 4-7 are on the MXP port.
*/
AnalogTrigger::AnalogTrigger(int channel)
: AnalogTrigger(new AnalogInput(channel)) {
m_ownsAnalog = true;
AddChild(m_analogInput);
}
/**
* Construct an analog trigger given an analog input.
*
* This should be used in the case of sharing an analog channel between the
* trigger and an analog input object.
*
* @param channel The pointer to the existing AnalogInput object
*/
AnalogTrigger::AnalogTrigger(AnalogInput* input) {
m_analogInput = input;
int32_t status = 0;
@@ -62,30 +48,6 @@ AnalogTrigger::~AnalogTrigger() {
}
}
/**
* Set the upper and lower limits of the analog trigger.
*
* The limits are given in ADC codes. If oversampling is used, the units must
* be scaled appropriately.
*
* @param lower The lower limit of the trigger in ADC codes (12-bit values).
* @param upper The upper limit of the trigger in ADC codes (12-bit values).
*/
void AnalogTrigger::SetLimitsRaw(int lower, int upper) {
if (StatusIsFatal()) return;
int32_t status = 0;
HAL_SetAnalogTriggerLimitsRaw(m_trigger, lower, upper, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Set the upper and lower limits of the analog trigger.
*
* The limits are given as floating point voltage values.
*
* @param lower The lower limit of the trigger in Volts.
* @param upper The upper limit of the trigger in Volts.
*/
void AnalogTrigger::SetLimitsVoltage(double lower, double upper) {
if (StatusIsFatal()) return;
int32_t status = 0;
@@ -93,15 +55,13 @@ void AnalogTrigger::SetLimitsVoltage(double lower, double upper) {
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Configure the analog trigger to use the averaged vs. raw values.
*
* If the value is true, then the averaged value is selected for the analog
* trigger, otherwise the immediate value is used.
*
* @param useAveragedValue If true, use the Averaged value, otherwise use the
* instantaneous reading
*/
void AnalogTrigger::SetLimitsRaw(int lower, int upper) {
if (StatusIsFatal()) return;
int32_t status = 0;
HAL_SetAnalogTriggerLimitsRaw(m_trigger, lower, upper, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
void AnalogTrigger::SetAveraged(bool useAveragedValue) {
if (StatusIsFatal()) return;
int32_t status = 0;
@@ -109,16 +69,6 @@ void AnalogTrigger::SetAveraged(bool useAveragedValue) {
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Configure the analog trigger to use a filtered value.
*
* The analog trigger will operate with a 3 point average rejection filter. This
* is designed to help with 360 degree pot applications for the period where
* the pot crosses through zero.
*
* @param useFilteredValue If true, use the 3 point rejection filter, otherwise
* use the unfiltered value
*/
void AnalogTrigger::SetFiltered(bool useFilteredValue) {
if (StatusIsFatal()) return;
int32_t status = 0;
@@ -126,25 +76,11 @@ void AnalogTrigger::SetFiltered(bool useFilteredValue) {
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Return the index of the analog trigger.
*
* This is the FPGA index of this analog trigger instance.
*
* @return The index of the analog trigger.
*/
int AnalogTrigger::GetIndex() const {
if (StatusIsFatal()) return -1;
return m_index;
}
/**
* Return the InWindow output of the analog trigger.
*
* True if the analog input is between the upper and lower limits.
*
* @return True if the analog input is between the upper and lower limits.
*/
bool AnalogTrigger::GetInWindow() {
if (StatusIsFatal()) return false;
int32_t status = 0;
@@ -153,16 +89,6 @@ bool AnalogTrigger::GetInWindow() {
return result;
}
/**
* Return the TriggerState output of the analog trigger.
*
* True if above upper limit.
* False if below lower limit.
* If in Hysteresis, maintain previous state.
*
* @return True if above upper limit. False if below lower limit. If in
* Hysteresis, maintain previous state.
*/
bool AnalogTrigger::GetTriggerState() {
if (StatusIsFatal()) return false;
int32_t status = 0;
@@ -171,15 +97,6 @@ bool AnalogTrigger::GetTriggerState() {
return result;
}
/**
* Creates an AnalogTriggerOutput object.
*
* Gets an output object that can be used for routing.
* Caller is responsible for deleting the AnalogTriggerOutput object.
*
* @param type An enum of the type of output object to create.
* @return A pointer to a new AnalogTriggerOutput object.
*/
std::shared_ptr<AnalogTriggerOutput> AnalogTrigger::CreateOutput(
AnalogTriggerType type) const {
if (StatusIsFatal()) return nullptr;

View File

@@ -14,24 +14,6 @@
using namespace frc;
/**
* Create an object that represents one of the four outputs from an analog
* trigger.
*
* Because this class derives from DigitalSource, it can be passed into routing
* functions for Counter, Encoder, etc.
*
* @param trigger A pointer to the trigger for which this is an output.
* @param outputType An enum that specifies the output on the trigger to
* represent.
*/
AnalogTriggerOutput::AnalogTriggerOutput(const AnalogTrigger& trigger,
AnalogTriggerType outputType)
: m_trigger(trigger), m_outputType(outputType) {
HAL_Report(HALUsageReporting::kResourceType_AnalogTriggerOutput,
trigger.GetIndex(), static_cast<uint8_t>(outputType));
}
AnalogTriggerOutput::~AnalogTriggerOutput() {
if (m_interrupt != HAL_kInvalidHandle) {
int32_t status = 0;
@@ -41,11 +23,6 @@ AnalogTriggerOutput::~AnalogTriggerOutput() {
}
}
/**
* Get the state of the analog trigger output.
*
* @return The state of the analog trigger output.
*/
bool AnalogTriggerOutput::Get() const {
int32_t status = 0;
bool result = HAL_GetAnalogTriggerOutput(
@@ -55,28 +32,23 @@ bool AnalogTriggerOutput::Get() const {
return result;
}
/**
* @return The HAL Handle to the specified source.
*/
HAL_Handle AnalogTriggerOutput::GetPortHandleForRouting() const {
return m_trigger.m_trigger;
}
/**
* Is source an AnalogTrigger
*/
bool AnalogTriggerOutput::IsAnalogTrigger() const { return true; }
/**
* @return The type of analog trigger output to be used.
*/
AnalogTriggerType AnalogTriggerOutput::GetAnalogTriggerTypeForRouting() const {
return m_outputType;
}
/**
* @return The channel of the source.
*/
bool AnalogTriggerOutput::IsAnalogTrigger() const { return true; }
int AnalogTriggerOutput::GetChannel() const { return m_trigger.m_index; }
void AnalogTriggerOutput::InitSendable(SendableBuilder&) {}
AnalogTriggerOutput::AnalogTriggerOutput(const AnalogTrigger& trigger,
AnalogTriggerType outputType)
: m_trigger(trigger), m_outputType(outputType) {
HAL_Report(HALUsageReporting::kResourceType_AnalogTriggerOutput,
trigger.GetIndex(), static_cast<uint8_t>(outputType));
}

View File

@@ -15,11 +15,6 @@
using namespace frc;
/**
* Constructor.
*
* @param range The range the accelerometer will measure
*/
BuiltInAccelerometer::BuiltInAccelerometer(Range range) {
SetRange(range);
@@ -39,19 +34,10 @@ void BuiltInAccelerometer::SetRange(Range range) {
HAL_SetAccelerometerActive(true);
}
/**
* @return The acceleration of the roboRIO along the X axis in g-forces
*/
double BuiltInAccelerometer::GetX() { return HAL_GetAccelerometerX(); }
/**
* @return The acceleration of the roboRIO along the Y axis in g-forces
*/
double BuiltInAccelerometer::GetY() { return HAL_GetAccelerometerY(); }
/**
* @return The acceleration of the roboRIO along the Z axis in g-forces
*/
double BuiltInAccelerometer::GetZ() { return HAL_GetAccelerometerZ(); }
void BuiltInAccelerometer::InitSendable(SendableBuilder& builder) {

View File

@@ -9,42 +9,12 @@
using namespace frc;
/**
* Specifies the command to run when a button is first pressed.
*
* @param command The pointer to the command to run
*/
void Button::WhenPressed(Command* command) { WhenActive(command); }
/**
* Specifies the command to be scheduled while the button is pressed.
*
* The command will be scheduled repeatedly while the button is pressed and will
* be canceled when the button is released.
*
* @param command The pointer to the command to run
*/
void Button::WhileHeld(Command* command) { WhileActive(command); }
/**
* Specifies the command to run when the button is released.
*
* The command will be scheduled a single time.
*
* @param command The pointer to the command to run
*/
void Button::WhenReleased(Command* command) { WhenInactive(command); }
/**
* Cancels the specificed command when the button is pressed.
*
* @param command The command to be canceled
*/
void Button::CancelWhenPressed(Command* command) { CancelWhenActive(command); }
/**
* Toggle the specified command when the button is pressed.
*
* @param command The command to be toggled
*/
void Button::ToggleWhenPressed(Command* command) { ToggleWhenActive(command); }

View File

@@ -11,10 +11,6 @@
using namespace frc;
/**
* Create a new CAN communication interface with the specific device ID.
* The device ID is 6 bits (0-63)
*/
CAN::CAN(int deviceId) {
int32_t status = 0;
m_handle =
@@ -28,9 +24,6 @@ CAN::CAN(int deviceId) {
// HAL_Report(HALUsageReporting::kResourceType_CAN, deviceId);
}
/**
* Closes the CAN communication.
*/
CAN::~CAN() {
if (StatusIsFatal()) return;
if (m_handle != HAL_kInvalidHandle) {
@@ -39,29 +32,12 @@ CAN::~CAN() {
}
}
/**
* Write a packet to the CAN device with a specific ID. This ID is 10 bits.
*
* @param data The data to write (8 bytes max)
* @param length The data length to write
* @param apiId The API ID to write.
*/
void CAN::WritePacket(const uint8_t* data, int length, int apiId) {
int32_t status = 0;
HAL_WriteCANPacket(m_handle, data, length, apiId, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Write a repeating packet to the CAN device with a specific ID. This ID is 10
* bits. The RoboRIO will automatically repeat the packet at the specified
* interval
*
* @param data The data to write (8 bytes max)
* @param length The data length to write
* @param apiId The API ID to write.
* @param repeatMs The period to repeat the packet at.
*/
void CAN::WritePacketRepeating(const uint8_t* data, int length, int apiId,
int repeatMs) {
int32_t status = 0;
@@ -69,25 +45,12 @@ void CAN::WritePacketRepeating(const uint8_t* data, int length, int apiId,
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Stop a repeating packet with a specific ID. This ID is 10 bits.
*
* @param apiId The API ID to stop repeating
*/
void CAN::StopPacketRepeating(int apiId) {
int32_t status = 0;
HAL_StopCANPacketRepeating(m_handle, apiId, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Read a new CAN packet. This will only return properly once per packet
* received. Multiple calls without receiving another packet will return false.
*
* @param apiId The API ID to read.
* @param data Storage for the received data.
* @return True if the data is valid, otherwise false.
*/
bool CAN::ReadPacketNew(int apiId, CANData* data) {
int32_t status = 0;
HAL_ReadCANPacketNew(m_handle, apiId, data->data, &data->length,
@@ -103,14 +66,6 @@ bool CAN::ReadPacketNew(int apiId, CANData* data) {
}
}
/**
* Read a CAN packet. The will continuously return the last packet received,
* without accounting for packet age.
*
* @param apiId The API ID to read.
* @param data Storage for the received data.
* @return True if the data is valid, otherwise false.
*/
bool CAN::ReadPacketLatest(int apiId, CANData* data) {
int32_t status = 0;
HAL_ReadCANPacketLatest(m_handle, apiId, data->data, &data->length,
@@ -126,15 +81,6 @@ bool CAN::ReadPacketLatest(int apiId, CANData* data) {
}
}
/**
* Read a CAN packet. The will return the last packet received until the
* packet is older then the requested timeout. Then it will return false.
*
* @param apiId The API ID to read.
* @param timeoutMs The timeout time for the packet
* @param data Storage for the received data.
* @return True if the data is valid, otherwise false.
*/
bool CAN::ReadPacketTimeout(int apiId, int timeoutMs, CANData* data) {
int32_t status = 0;
HAL_ReadCANPacketTimeout(m_handle, apiId, data->data, &data->length,
@@ -151,20 +97,6 @@ bool CAN::ReadPacketTimeout(int apiId, int timeoutMs, CANData* data) {
}
}
/**
* Read a CAN packet. The will return the last packet received until the
* packet is older then the requested timeout. Then it will return false.
* The period parameter is used when you know the packet is sent at specific
* intervals, so calls will not attempt to read a new packet from the
* network until that period has passed. We do not recommend users use this
* API unless they know the implications.
*
* @param apiId The API ID to read.
* @param timeoutMs The timeout time for the packet
* @param periodMs The usual period for the packet
* @param data Storage for the received data.
* @return True if the data is valid, otherwise false.
*/
bool CAN::ReadPeriodicPacket(int apiId, int timeoutMs, int periodMs,
CANData* data) {
int32_t status = 0;

View File

@@ -21,35 +21,12 @@ using namespace frc;
int Command::m_commandCounter = 0;
/**
* Creates a new command.
*
* The name of this command will be default.
*/
Command::Command() : Command("", -1.0) {}
/**
* Creates a new command with the given name and no timeout.
*
* @param name the name for this command
*/
Command::Command(const wpi::Twine& name) : Command(name, -1.0) {}
/**
* Creates a new command with the given timeout and a default name.
*
* @param timeout the time (in seconds) before this command "times out"
* @see IsTimedOut()
*/
Command::Command(double timeout) : Command("", timeout) {}
/**
* Creates a new command with the given name and timeout.
*
* @param name the name of the command
* @param timeout the time (in seconds) before this command "times out"
* @see IsTimedOut()
*/
Command::Command(const wpi::Twine& name, double timeout) : SendableBase(false) {
// We use -1.0 to indicate no timeout.
if (timeout < 0.0 && timeout != -1.0)
@@ -66,35 +43,6 @@ Command::Command(const wpi::Twine& name, double timeout) : SendableBase(false) {
}
}
/**
* Get the ID (sequence number) for this command.
*
* The ID is a unique sequence number that is incremented for each command.
*
* @return The ID of this command
*/
int Command::GetID() const { return m_commandID; }
/**
* Sets the timeout of this command.
*
* @param timeout the timeout (in seconds)
* @see IsTimedOut()
*/
void Command::SetTimeout(double timeout) {
if (timeout < 0.0)
wpi_setWPIErrorWithContext(ParameterOutOfRange, "timeout < 0.0");
else
m_timeout = timeout;
}
/**
* Returns the time since this command was initialized (in seconds).
*
* This function will work even if there is no specified timeout.
*
* @return the time since this command was initialized (in seconds).
*/
double Command::TimeSinceInitialized() const {
if (m_startTime < 0.0)
return 0.0;
@@ -102,16 +50,6 @@ double Command::TimeSinceInitialized() const {
return Timer::GetFPGATimestamp() - m_startTime;
}
/**
* This method specifies that the given Subsystem is used by this command.
*
* This method is crucial to the functioning of the Command System in general.
*
* Note that the recommended way to call this method is in the constructor.
*
* @param subsystem The Subsystem required
* @see Subsystem
*/
void Command::Requires(Subsystem* subsystem) {
if (!AssertUnlocked("Can not add new requirement to command")) return;
@@ -121,34 +59,6 @@ void Command::Requires(Subsystem* subsystem) {
wpi_setWPIErrorWithContext(NullParameter, "subsystem");
}
/**
* Called when the command has been removed.
*
* This will call Interrupted() or End().
*/
void Command::Removed() {
if (m_initialized) {
if (IsCanceled()) {
Interrupted();
_Interrupted();
} else {
End();
_End();
}
}
m_initialized = false;
m_canceled = false;
m_running = false;
m_completed = true;
}
/**
* Starts up the command. Gets the command ready to start.
*
* Note that the command will eventually start, however it will not necessarily
* do so immediately, and may in fact be canceled before initialize is even
* called.
*/
void Command::Start() {
LockChanges();
if (m_parent != nullptr)
@@ -160,11 +70,6 @@ void Command::Start() {
Scheduler::GetInstance()->AddCommand(this);
}
/**
* The run method is used internally to actually run the commands.
*
* @return Whether or not the command should stay within the Scheduler.
*/
bool Command::Run() {
if (!m_runWhenDisabled && m_parent == nullptr && RobotState::IsDisabled())
Cancel();
@@ -182,86 +87,56 @@ bool Command::Run() {
return !IsFinished();
}
/**
* The initialize method is called the first time this Command is run after
* being started.
*/
void Command::Initialize() {}
void Command::Cancel() {
if (m_parent != nullptr)
wpi_setWPIErrorWithContext(
CommandIllegalUse,
"Can not cancel a command that is part of a command group");
/**
* The execute method is called repeatedly until this Command either finishes
* or is canceled.
*/
void Command::Execute() {}
/**
* Called when the command ended peacefully. This is where you may want to wrap
* up loose ends, like shutting off a motor that was being used in the command.
*/
void Command::End() {}
/**
* Called when the command ends because somebody called Cancel() or another
* command shared the same requirements as this one, and booted it out.
*
* This is where you may want to wrap up loose ends, like shutting off a motor
* that was being used in the command.
*
* Generally, it is useful to simply call the End() method within this method,
* as done here.
*/
void Command::Interrupted() { End(); }
void Command::_Initialize() { m_completed = false; }
void Command::_Interrupted() { m_completed = true; }
void Command::_Execute() {}
void Command::_End() { m_completed = true; }
/**
* Called to indicate that the timer should start.
*
* This is called right before Initialize() is, inside the Run() method.
*/
void Command::StartTiming() { m_startTime = Timer::GetFPGATimestamp(); }
/**
* Returns whether or not the TimeSinceInitialized() method returns a number
* which is greater than or equal to the timeout for the command.
*
* If there is no timeout, this will always return false.
*
* @return whether the time has expired
*/
bool Command::IsTimedOut() const {
return m_timeout != -1 && TimeSinceInitialized() >= m_timeout;
_Cancel();
}
bool Command::IsRunning() const { return m_running; }
bool Command::IsInitialized() const { return m_initialized; }
bool Command::IsCompleted() const { return m_completed; }
bool Command::IsCanceled() const { return m_canceled; }
bool Command::IsInterruptible() const { return m_interruptible; }
void Command::SetInterruptible(bool interruptible) {
m_interruptible = interruptible;
}
bool Command::DoesRequire(Subsystem* system) const {
return m_requirements.count(system) > 0;
}
/**
* Returns the requirements (as an std::set of Subsystem pointers) of this
* command.
*
* @return The requirements (as an std::set of Subsystem pointers) of this
* command
*/
Command::SubsystemSet Command::GetRequirements() const {
return m_requirements;
}
/**
* Prevents further changes from being made.
*/
void Command::LockChanges() { m_locked = true; }
CommandGroup* Command::GetGroup() const { return m_parent; }
void Command::SetRunWhenDisabled(bool run) { m_runWhenDisabled = run; }
bool Command::WillRunWhenDisabled() const { return m_runWhenDisabled; }
int Command::GetID() const { return m_commandID; }
void Command::SetTimeout(double timeout) {
if (timeout < 0.0)
wpi_setWPIErrorWithContext(ParameterOutOfRange, "timeout < 0.0");
else
m_timeout = timeout;
}
bool Command::IsTimedOut() const {
return m_timeout != -1 && TimeSinceInitialized() >= m_timeout;
}
/**
* If changes are locked, then this will generate a CommandIllegalUse error.
*
* @param message The message to report on error (it is appended by a default
* message)
* @return True if assert passed, false if assert failed.
*/
bool Command::AssertUnlocked(const std::string& message) {
if (m_locked) {
std::string buf =
@@ -272,11 +147,6 @@ bool Command::AssertUnlocked(const std::string& message) {
return true;
}
/**
* Sets the parent of this command. No actual change is made to the group.
*
* @param parent the parent
*/
void Command::SetParent(CommandGroup* parent) {
if (parent == nullptr) {
wpi_setWPIErrorWithContext(NullParameter, "parent");
@@ -290,153 +160,55 @@ void Command::SetParent(CommandGroup* parent) {
}
}
/**
* Returns whether the command has a parent.
*
* @param True if the command has a parent.
*/
bool Command::IsParented() const { return m_parent != nullptr; }
/**
* Clears list of subsystem requirements.
*
* This is only used by ConditionalCommand so cancelling the chosen command
* works properly in CommandGroup.
*/
void Command::ClearRequirements() { m_requirements.clear(); }
/**
* This is used internally to mark that the command has been started.
*
* The lifecycle of a command is:
*
* StartRunning() is called. Run() is called (multiple times potentially).
* Removed() is called.
*
* It is very important that StartRunning() and Removed() be called in order or
* some assumptions of the code will be broken.
*/
void Command::Initialize() {}
void Command::Execute() {}
void Command::End() {}
void Command::Interrupted() { End(); }
void Command::_Initialize() { m_completed = false; }
void Command::_Interrupted() { m_completed = true; }
void Command::_Execute() {}
void Command::_End() { m_completed = true; }
void Command::_Cancel() {
if (IsRunning()) m_canceled = true;
}
void Command::LockChanges() { m_locked = true; }
void Command::Removed() {
if (m_initialized) {
if (IsCanceled()) {
Interrupted();
_Interrupted();
} else {
End();
_End();
}
}
m_initialized = false;
m_canceled = false;
m_running = false;
m_completed = true;
}
void Command::StartRunning() {
m_running = true;
m_startTime = -1;
m_completed = false;
}
/**
* Returns whether or not the command is running.
*
* This may return true even if the command has just been canceled, as it may
* not have yet called Interrupted().
*
* @return whether or not the command is running
*/
bool Command::IsRunning() const { return m_running; }
/**
* Returns whether or not the command has been initialized.
*
* @return whether or not the command has been initialized.
*/
bool Command::IsInitialized() const { return m_initialized; }
/**
* Returns whether or not the command has completed running.
*
* @return whether or not the command has completed running.
*/
bool Command::IsCompleted() const { return m_completed; }
/**
* This will cancel the current command.
*
* This will cancel the current command eventually. It can be called multiple
* times. And it can be called when the command is not running. If the command
* is running though, then the command will be marked as canceled and eventually
* removed.
*
* A command can not be canceled if it is a part of a command group, you must
* cancel the command group instead.
*/
void Command::Cancel() {
if (m_parent != nullptr)
wpi_setWPIErrorWithContext(
CommandIllegalUse,
"Can not cancel a command that is part of a command group");
_Cancel();
}
/**
* This works like Cancel(), except that it doesn't throw an exception if it is
* a part of a command group.
*
* Should only be called by the parent command group.
*/
void Command::_Cancel() {
if (IsRunning()) m_canceled = true;
}
/**
* Returns whether or not this has been canceled.
*
* @return whether or not this has been canceled
*/
bool Command::IsCanceled() const { return m_canceled; }
/**
* Returns whether or not this command can be interrupted.
*
* @return whether or not this command can be interrupted
*/
bool Command::IsInterruptible() const { return m_interruptible; }
/**
* Sets whether or not this command can be interrupted.
*
* @param interruptible whether or not this command can be interrupted
*/
void Command::SetInterruptible(bool interruptible) {
m_interruptible = interruptible;
}
/**
* Checks if the command requires the given Subsystem.
*
* @param system the system
* @return whether or not the subsystem is required (false if given nullptr)
*/
bool Command::DoesRequire(Subsystem* system) const {
return m_requirements.count(system) > 0;
}
/**
* Returns the CommandGroup that this command is a part of.
*
* Will return null if this Command is not in a group.
*
* @return The CommandGroup that this command is a part of (or null if not in
* group)
*/
CommandGroup* Command::GetGroup() const { return m_parent; }
/**
* Sets whether or not this Command should run when the robot is disabled.
*
* By default a command will not run when the robot is disabled, and will in
* fact be canceled.
*
* @param run Whether this command should run when the robot is disabled.
*/
void Command::SetRunWhenDisabled(bool run) { m_runWhenDisabled = run; }
/**
* Returns whether or not this Command will run when the robot is disabled, or
* if it will cancel itself.
*
* @return Whether this Command will run when the robot is disabled, or if it
* will cancel itself.
*/
bool Command::WillRunWhenDisabled() const { return m_runWhenDisabled; }
void Command::StartTiming() { m_startTime = Timer::GetFPGATimestamp(); }
void Command::InitSendable(SendableBuilder& builder) {
builder.SetSmartDashboardType("Command");

View File

@@ -11,25 +11,8 @@
using namespace frc;
/**
* Creates a new CommandGroup with the given name.
*
* @param name The name for this command group
*/
CommandGroup::CommandGroup(const wpi::Twine& name) : Command(name) {}
/**
* Adds a new Command to the group. The Command will be started after all the
* previously added Commands.
*
* Note that any requirements the given Command has will be added to the group.
* For this reason, a Command's requirements can not be changed after being
* added to a group.
*
* It is recommended that this method be called in the constructor.
*
* @param command The Command to be added
*/
void CommandGroup::AddSequential(Command* command) {
if (command == nullptr) {
wpi_setWPIErrorWithContext(NullParameter, "command");
@@ -48,23 +31,6 @@ void CommandGroup::AddSequential(Command* command) {
Requires(*iter);
}
/**
* Adds a new Command to the group with a given timeout. The Command will be
* started after all the previously added commands.
*
* Once the Command is started, it will be run until it finishes or the time
* expires, whichever is sooner. Note that the given Command will have no
* knowledge that it is on a timer.
*
* Note that any requirements the given Command has will be added to the group.
* For this reason, a Command's requirements can not be changed after being
* added to a group.
*
* It is recommended that this method be called in the constructor.
*
* @param command The Command to be added
* @param timeout The timeout (in seconds)
*/
void CommandGroup::AddSequential(Command* command, double timeout) {
if (command == nullptr) {
wpi_setWPIErrorWithContext(NullParameter, "command");
@@ -87,24 +53,6 @@ void CommandGroup::AddSequential(Command* command, double timeout) {
Requires(*iter);
}
/**
* Adds a new child Command to the group. The Command will be started after all
* the previously added Commands.
*
* Instead of waiting for the child to finish, a CommandGroup will have it run
* at the same time as the subsequent Commands. The child will run until either
* it finishes, a new child with conflicting requirements is started, or the
* main sequence runs a Command with conflicting requirements. In the latter two
* cases, the child will be canceled even if it says it can't be interrupted.
*
* Note that any requirements the given Command has will be added to the group.
* For this reason, a Command's requirements can not be changed after being
* added to a group.
*
* It is recommended that this method be called in the constructor.
*
* @param command The command to be added
*/
void CommandGroup::AddParallel(Command* command) {
if (command == nullptr) {
wpi_setWPIErrorWithContext(NullParameter, "command");
@@ -123,30 +71,6 @@ void CommandGroup::AddParallel(Command* command) {
Requires(*iter);
}
/**
* Adds a new child Command to the group with the given timeout. The Command
* will be started after all the previously added Commands.
*
* Once the Command is started, it will run until it finishes, is interrupted,
* or the time expires, whichever is sooner. Note that the given Command will
* have no knowledge that it is on a timer.
*
* Instead of waiting for the child to finish, a CommandGroup will have it run
* at the same time as the subsequent Commands. The child will run until either
* it finishes, the timeout expires, a new child with conflicting requirements
* is started, or the main sequence runs a Command with conflicting
* requirements. In the latter two cases, the child will be canceled even if it
* says it can't be interrupted.
*
* Note that any requirements the given Command has will be added to the group.
* For this reason, a Command's requirements can not be changed after being
* added to a group.
*
* It is recommended that this method be called in the constructor.
*
* @param command The command to be added
* @param timeout The timeout (in seconds)
*/
void CommandGroup::AddParallel(Command* command, double timeout) {
if (command == nullptr) {
wpi_setWPIErrorWithContext(NullParameter, "command");
@@ -169,6 +93,37 @@ void CommandGroup::AddParallel(Command* command, double timeout) {
Requires(*iter);
}
bool CommandGroup::IsInterruptible() const {
if (!Command::IsInterruptible()) return false;
if (m_currentCommandIndex != -1 &&
static_cast<size_t>(m_currentCommandIndex) < m_commands.size()) {
Command* cmd = m_commands[m_currentCommandIndex].m_command;
if (!cmd->IsInterruptible()) return false;
}
for (auto iter = m_children.cbegin(); iter != m_children.cend(); iter++) {
if (!iter->m_command->IsInterruptible()) return false;
}
return true;
}
int CommandGroup::GetSize() const { return m_children.size(); }
void CommandGroup::Initialize() {}
void CommandGroup::Execute() {}
bool CommandGroup::IsFinished() {
return static_cast<size_t>(m_currentCommandIndex) >= m_commands.size() &&
m_children.empty();
}
void CommandGroup::End() {}
void CommandGroup::Interrupted() {}
void CommandGroup::_Initialize() { m_currentCommandIndex = -1; }
void CommandGroup::_Execute() {
@@ -258,39 +213,6 @@ void CommandGroup::_End() {
void CommandGroup::_Interrupted() { _End(); }
// Can be overwritten by teams
void CommandGroup::Initialize() {}
// Can be overwritten by teams
void CommandGroup::Execute() {}
// Can be overwritten by teams
void CommandGroup::End() {}
// Can be overwritten by teams
void CommandGroup::Interrupted() {}
bool CommandGroup::IsFinished() {
return static_cast<size_t>(m_currentCommandIndex) >= m_commands.size() &&
m_children.empty();
}
bool CommandGroup::IsInterruptible() const {
if (!Command::IsInterruptible()) return false;
if (m_currentCommandIndex != -1 &&
static_cast<size_t>(m_currentCommandIndex) < m_commands.size()) {
Command* cmd = m_commands[m_currentCommandIndex].m_command;
if (!cmd->IsInterruptible()) return false;
}
for (auto iter = m_children.cbegin(); iter != m_children.cend(); iter++) {
if (!iter->m_command->IsInterruptible()) return false;
}
return true;
}
void CommandGroup::CancelConflicts(Command* command) {
for (auto childIter = m_children.begin(); childIter != m_children.end();) {
Command* child = childIter->m_command;
@@ -310,5 +232,3 @@ void CommandGroup::CancelConflicts(Command* command) {
if (!erased) childIter++;
}
}
int CommandGroup::GetSize() const { return m_children.size(); }

View File

@@ -24,12 +24,6 @@ static void RequireAll(Command& command, Command* onTrue, Command* onFalse) {
}
}
/**
* Creates a new ConditionalCommand with given onTrue and onFalse Commands.
*
* @param onTrue The Command to execute if Condition() returns true
* @param onFalse The Command to execute if Condition() returns false
*/
ConditionalCommand::ConditionalCommand(Command* onTrue, Command* onFalse) {
m_onTrue = onTrue;
m_onFalse = onFalse;
@@ -37,13 +31,6 @@ ConditionalCommand::ConditionalCommand(Command* onTrue, Command* onFalse) {
RequireAll(*this, onTrue, onFalse);
}
/**
* Creates a new ConditionalCommand with given onTrue and onFalse Commands.
*
* @param name The name for this command group
* @param onTrue The Command to execute if Condition() returns true
* @param onFalse The Command to execute if Condition() returns false
*/
ConditionalCommand::ConditionalCommand(const wpi::Twine& name, Command* onTrue,
Command* onFalse)
: Command(name) {

View File

@@ -9,11 +9,6 @@
using namespace frc;
/**
* Creates a new InstantCommand with the given name.
*
* @param name The name for this command
*/
InstantCommand::InstantCommand(const wpi::Twine& name) : Command(name) {}
bool InstantCommand::IsFinished() { return true; }

View File

@@ -11,29 +11,12 @@
using namespace frc;
/**
* Instantiates a PIDSubsystem that will use the given P, I, and D values.
*
* @param name the name
* @param p the proportional value
* @param i the integral value
* @param d the derivative value
*/
PIDSubsystem::PIDSubsystem(const wpi::Twine& name, double p, double i, double d)
: Subsystem(name) {
m_controller = std::make_shared<PIDController>(p, i, d, this, this);
AddChild("PIDController", m_controller);
}
/**
* Instantiates a PIDSubsystem that will use the given P, I, and D values.
*
* @param name the name
* @param p the proportional value
* @param i the integral value
* @param d the derivative value
* @param f the feedforward value
*/
PIDSubsystem::PIDSubsystem(const wpi::Twine& name, double p, double i, double d,
double f)
: Subsystem(name) {
@@ -41,19 +24,6 @@ PIDSubsystem::PIDSubsystem(const wpi::Twine& name, double p, double i, double d,
AddChild("PIDController", m_controller);
}
/**
* Instantiates a PIDSubsystem that will use the given P, I, and D values.
*
* It will also space the time between PID loop calculations to be equal to the
* given period.
*
* @param name the name
* @param p the proportional value
* @param i the integral value
* @param d the derivative value
* @param f the feedfoward value
* @param period the time (in seconds) between calculations
*/
PIDSubsystem::PIDSubsystem(const wpi::Twine& name, double p, double i, double d,
double f, double period)
: Subsystem(name) {
@@ -62,49 +32,18 @@ PIDSubsystem::PIDSubsystem(const wpi::Twine& name, double p, double i, double d,
AddChild("PIDController", m_controller);
}
/**
* Instantiates a PIDSubsystem that will use the given P, I, and D values.
*
* It will use the class name as its name.
*
* @param p the proportional value
* @param i the integral value
* @param d the derivative value
*/
PIDSubsystem::PIDSubsystem(double p, double i, double d)
: Subsystem("PIDSubsystem") {
m_controller = std::make_shared<PIDController>(p, i, d, this, this);
AddChild("PIDController", m_controller);
}
/**
* Instantiates a PIDSubsystem that will use the given P, I, and D values.
*
* It will use the class name as its name.
*
* @param p the proportional value
* @param i the integral value
* @param d the derivative value
* @param f the feedforward value
*/
PIDSubsystem::PIDSubsystem(double p, double i, double d, double f)
: Subsystem("PIDSubsystem") {
m_controller = std::make_shared<PIDController>(p, i, d, f, this, this);
AddChild("PIDController", m_controller);
}
/**
* Instantiates a PIDSubsystem that will use the given P, I, and D values.
*
* It will use the class name as its name. It will also space the time
* between PID loop calculations to be equal to the given period.
*
* @param p the proportional value
* @param i the integral value
* @param d the derivative value
* @param f the feedforward value
* @param period the time (in seconds) between calculations
*/
PIDSubsystem::PIDSubsystem(double p, double i, double d, double f,
double period)
: Subsystem("PIDSubsystem") {
@@ -113,128 +52,46 @@ PIDSubsystem::PIDSubsystem(double p, double i, double d, double f,
AddChild("PIDController", m_controller);
}
/**
* Enables the internal PIDController.
*/
void PIDSubsystem::Enable() { m_controller->Enable(); }
/**
* Disables the internal PIDController.
*/
void PIDSubsystem::Disable() { m_controller->Disable(); }
/**
* Returns the PIDController used by this PIDSubsystem.
*
* Use this if you would like to fine tune the PID loop.
*
* @return The PIDController used by this PIDSubsystem
*/
std::shared_ptr<PIDController> PIDSubsystem::GetPIDController() {
return m_controller;
}
/**
* Sets the setpoint to the given value.
*
* If SetRange() was called, then the given setpoint will be trimmed to fit
* within the range.
*
* @param setpoint the new setpoint
*/
void PIDSubsystem::SetSetpoint(double setpoint) {
m_controller->SetSetpoint(setpoint);
}
/**
* Adds the given value to the setpoint.
*
* If SetRange() was used, then the bounds will still be honored by this method.
*
* @param deltaSetpoint the change in the setpoint
*/
void PIDSubsystem::SetSetpointRelative(double deltaSetpoint) {
SetSetpoint(GetSetpoint() + deltaSetpoint);
}
/**
* Return the current setpoint.
*
* @return The current setpoint
*/
double PIDSubsystem::GetSetpoint() { return m_controller->GetSetpoint(); }
/**
* Sets the maximum and minimum values expected from the input.
*
* @param minimumInput the minimum value expected from the input
* @param maximumInput the maximum value expected from the output
*/
void PIDSubsystem::SetInputRange(double minimumInput, double maximumInput) {
m_controller->SetInputRange(minimumInput, maximumInput);
}
/**
* Sets the maximum and minimum values to write.
*
* @param minimumOutput the minimum value to write to the output
* @param maximumOutput the maximum value to write to the output
*/
void PIDSubsystem::SetOutputRange(double minimumOutput, double maximumOutput) {
m_controller->SetOutputRange(minimumOutput, maximumOutput);
}
/**
* Set the absolute error which is considered tolerable for use with
* OnTarget.
*
* @param absValue absolute error which is tolerable
*/
void PIDSubsystem::SetAbsoluteTolerance(double absValue) {
m_controller->SetAbsoluteTolerance(absValue);
}
/**
* Set the percentage error which is considered tolerable for use with
* OnTarget().
*
* @param percent percentage error which is tolerable
*/
void PIDSubsystem::SetPercentTolerance(double percent) {
m_controller->SetPercentTolerance(percent);
}
/**
* Return true if the error is within the percentage of the total input range,
* determined by SetTolerance().
*
* This asssumes that the maximum and minimum input were set using SetInput().
* Use OnTarget() in the IsFinished() method of commands that use this
* subsystem.
*
* Currently this just reports on target as the actual value passes through the
* setpoint. Ideally it should be based on being within the tolerance for some
* period of time.
*
* @return True if the error is within the percentage tolerance of the input
* range
*/
bool PIDSubsystem::OnTarget() const { return m_controller->OnTarget(); }
/**
* Returns the current position.
*
* @return the current position
*/
double PIDSubsystem::GetPosition() { return ReturnPIDInput(); }
/**
* Returns the current rate.
*
* @return the current rate
*/
double PIDSubsystem::GetRate() { return ReturnPIDInput(); }
void PIDSubsystem::PIDWrite(double output) { UsePIDOutput(output); }
double PIDSubsystem::PIDGet() { return ReturnPIDInput(); }
void PIDSubsystem::SetSetpoint(double setpoint) {
m_controller->SetSetpoint(setpoint);
}
void PIDSubsystem::SetSetpointRelative(double deltaSetpoint) {
SetSetpoint(GetSetpoint() + deltaSetpoint);
}
void PIDSubsystem::SetInputRange(double minimumInput, double maximumInput) {
m_controller->SetInputRange(minimumInput, maximumInput);
}
void PIDSubsystem::SetOutputRange(double minimumOutput, double maximumOutput) {
m_controller->SetOutputRange(minimumOutput, maximumOutput);
}
double PIDSubsystem::GetSetpoint() { return m_controller->GetSetpoint(); }
double PIDSubsystem::GetPosition() { return ReturnPIDInput(); }
double PIDSubsystem::GetRate() { return ReturnPIDInput(); }
void PIDSubsystem::SetAbsoluteTolerance(double absValue) {
m_controller->SetAbsoluteTolerance(absValue);
}
void PIDSubsystem::SetPercentTolerance(double percent) {
m_controller->SetPercentTolerance(percent);
}
bool PIDSubsystem::OnTarget() const { return m_controller->OnTarget(); }
std::shared_ptr<PIDController> PIDSubsystem::GetPIDController() {
return m_controller;
}

View File

@@ -18,31 +18,11 @@
using namespace frc;
Scheduler::Scheduler() {
HLUsageReporting::ReportScheduler();
SetName("Scheduler");
}
/**
* Returns the Scheduler, creating it if one does not exist.
*
* @return the Scheduler
*/
Scheduler* Scheduler::GetInstance() {
static Scheduler instance;
return &instance;
}
void Scheduler::SetEnabled(bool enabled) { m_enabled = enabled; }
/**
* Add a command to be scheduled later.
*
* In any pass through the scheduler, all commands are added to the additions
* list, then at the end of the pass, they are all scheduled.
*
* @param command The command to be scheduled
*/
void Scheduler::AddCommand(Command* command) {
std::lock_guard<wpi::mutex> lock(m_additionsMutex);
if (std::find(m_additions.begin(), m_additions.end(), command) !=
@@ -56,63 +36,14 @@ void Scheduler::AddButton(ButtonScheduler* button) {
m_buttons.push_back(button);
}
void Scheduler::ProcessCommandAddition(Command* command) {
if (command == nullptr) return;
// Check to make sure no adding during adding
if (m_adding) {
wpi_setWPIErrorWithContext(IncompatibleState,
"Can not start command from cancel method");
void Scheduler::RegisterSubsystem(Subsystem* subsystem) {
if (subsystem == nullptr) {
wpi_setWPIErrorWithContext(NullParameter, "subsystem");
return;
}
// Only add if not already in
auto found = m_commands.find(command);
if (found == m_commands.end()) {
// Check that the requirements can be had
Command::SubsystemSet requirements = command->GetRequirements();
for (Command::SubsystemSet::iterator iter = requirements.begin();
iter != requirements.end(); iter++) {
Subsystem* lock = *iter;
if (lock->GetCurrentCommand() != nullptr &&
!lock->GetCurrentCommand()->IsInterruptible())
return;
}
// Give it the requirements
m_adding = true;
for (Command::SubsystemSet::iterator iter = requirements.begin();
iter != requirements.end(); iter++) {
Subsystem* lock = *iter;
if (lock->GetCurrentCommand() != nullptr) {
lock->GetCurrentCommand()->Cancel();
Remove(lock->GetCurrentCommand());
}
lock->SetCurrentCommand(command);
}
m_adding = false;
m_commands.insert(command);
command->StartRunning();
m_runningCommandsChanged = true;
}
m_subsystems.insert(subsystem);
}
/**
* Runs a single iteration of the loop.
*
* This method should be called often in order to have a functioning
* Command system. The loop has five stages:
*
* <ol>
* <li>Poll the Buttons</li>
* <li>Execute/Remove the Commands</li>
* <li>Send values to SmartDashboard</li>
* <li>Add Commands</li>
* <li>Add Defaults</li>
* </ol>
*/
void Scheduler::Run() {
// Get button input (going backwards preserves button priority)
{
@@ -167,27 +98,6 @@ void Scheduler::Run() {
}
}
/**
* Registers a Subsystem to this Scheduler, so that the Scheduler might know if
* a default Command needs to be run.
*
* All Subsystems should call this.
*
* @param system the system
*/
void Scheduler::RegisterSubsystem(Subsystem* subsystem) {
if (subsystem == nullptr) {
wpi_setWPIErrorWithContext(NullParameter, "subsystem");
return;
}
m_subsystems.insert(subsystem);
}
/**
* Removes the Command from the Scheduler.
*
* @param command the command to remove
*/
void Scheduler::Remove(Command* command) {
if (command == nullptr) {
wpi_setWPIErrorWithContext(NullParameter, "command");
@@ -211,9 +121,6 @@ void Scheduler::RemoveAll() {
}
}
/**
* Completely resets the scheduler. Undefined behavior if running.
*/
void Scheduler::ResetAll() {
RemoveAll();
m_subsystems.clear();
@@ -225,6 +132,8 @@ void Scheduler::ResetAll() {
m_cancelEntry = nt::NetworkTableEntry();
}
void Scheduler::SetEnabled(bool enabled) { m_enabled = enabled; }
void Scheduler::InitSendable(SendableBuilder& builder) {
builder.SetSmartDashboardType("Scheduler");
m_namesEntry = builder.GetEntry("Names");
@@ -268,3 +177,51 @@ void Scheduler::InitSendable(SendableBuilder& builder) {
}
});
}
Scheduler::Scheduler() {
HLUsageReporting::ReportScheduler();
SetName("Scheduler");
}
void Scheduler::ProcessCommandAddition(Command* command) {
if (command == nullptr) return;
// Check to make sure no adding during adding
if (m_adding) {
wpi_setWPIErrorWithContext(IncompatibleState,
"Can not start command from cancel method");
return;
}
// Only add if not already in
auto found = m_commands.find(command);
if (found == m_commands.end()) {
// Check that the requirements can be had
Command::SubsystemSet requirements = command->GetRequirements();
for (Command::SubsystemSet::iterator iter = requirements.begin();
iter != requirements.end(); iter++) {
Subsystem* lock = *iter;
if (lock->GetCurrentCommand() != nullptr &&
!lock->GetCurrentCommand()->IsInterruptible())
return;
}
// Give it the requirements
m_adding = true;
for (Command::SubsystemSet::iterator iter = requirements.begin();
iter != requirements.end(); iter++) {
Subsystem* lock = *iter;
if (lock->GetCurrentCommand() != nullptr) {
lock->GetCurrentCommand()->Cancel();
Remove(lock->GetCurrentCommand());
}
lock->SetCurrentCommand(command);
}
m_adding = false;
m_commands.insert(command);
command->StartRunning();
m_runningCommandsChanged = true;
}
}

View File

@@ -15,37 +15,11 @@
using namespace frc;
/**
* Creates a subsystem with the given name.
*
* @param name the name of the subsystem
*/
Subsystem::Subsystem(const wpi::Twine& name) {
SetName(name, name);
Scheduler::GetInstance()->RegisterSubsystem(this);
}
/**
* Initialize the default command for this subsystem.
*
* This is meant to be the place to call SetDefaultCommand in a subsystem and
* will be called on all the subsystems by the CommandBase method before the
* program starts running by using the list of all registered Subsystems inside
* the Scheduler.
*
* This should be overridden by a Subsystem that has a default Command
*/
void Subsystem::InitDefaultCommand() {}
/**
* Sets the default command. If this is not called or is called with null,
* then there will be no default command for the subsystem.
*
* <b>WARNING:</b> This should <b>NOT</b> be called in a constructor if the
* subsystem is a singleton.
*
* @param command the default command (or null if there should be none)
*/
void Subsystem::SetDefaultCommand(Command* command) {
if (command == nullptr) {
m_defaultCommand = nullptr;
@@ -69,11 +43,6 @@ void Subsystem::SetDefaultCommand(Command* command) {
}
}
/**
* Returns the default command (or null if there is none).
*
* @return the default command
*/
Command* Subsystem::GetDefaultCommand() {
if (!m_initializedDefaultCommand) {
m_initializedDefaultCommand = true;
@@ -82,11 +51,6 @@ Command* Subsystem::GetDefaultCommand() {
return m_defaultCommand;
}
/**
* Returns the default command name, or empty string is there is none.
*
* @return the default command name
*/
wpi::StringRef Subsystem::GetDefaultCommandName() {
Command* defaultCommand = GetDefaultCommand();
if (defaultCommand) {
@@ -96,28 +60,13 @@ wpi::StringRef Subsystem::GetDefaultCommandName() {
}
}
/**
* Sets the current command.
*
* @param command the new current command
*/
void Subsystem::SetCurrentCommand(Command* command) {
m_currentCommand = command;
m_currentCommandChanged = true;
}
/**
* Returns the command which currently claims this subsystem.
*
* @return the command which currently claims this subsystem
*/
Command* Subsystem::GetCurrentCommand() const { return m_currentCommand; }
/**
* Returns the current command name, or empty string if no current command.
*
* @return the current command name
*/
wpi::StringRef Subsystem::GetCurrentCommandName() const {
Command* currentCommand = GetCurrentCommand();
if (currentCommand) {
@@ -127,82 +76,37 @@ wpi::StringRef Subsystem::GetCurrentCommandName() const {
}
}
/**
* When the run method of the scheduler is called this method will be called.
*/
void Subsystem::Periodic() {}
/**
* Call this to alert Subsystem that the current command is actually the
* command.
*
* Sometimes, the Subsystem is told that it has no command while the Scheduler
* is going through the loop, only to be soon after given a new one. This will
* avoid that situation.
*/
void Subsystem::ConfirmCommand() {
if (m_currentCommandChanged) m_currentCommandChanged = false;
}
void Subsystem::InitDefaultCommand() {}
/**
* Associate a Sendable with this Subsystem.
* Also update the child's name.
*
* @param name name to give child
* @param child sendable
*/
void Subsystem::AddChild(const wpi::Twine& name,
std::shared_ptr<Sendable> child) {
AddChild(name, *child);
}
/**
* Associate a Sendable with this Subsystem.
* Also update the child's name.
*
* @param name name to give child
* @param child sendable
*/
void Subsystem::AddChild(const wpi::Twine& name, Sendable* child) {
AddChild(name, *child);
}
/**
* Associate a Sendable with this Subsystem.
* Also update the child's name.
*
* @param name name to give child
* @param child sendable
*/
void Subsystem::AddChild(const wpi::Twine& name, Sendable& child) {
child.SetName(GetSubsystem(), name);
LiveWindow::GetInstance()->Add(&child);
}
/**
* Associate a {@link Sendable} with this Subsystem.
*
* @param child sendable
*/
void Subsystem::AddChild(std::shared_ptr<Sendable> child) { AddChild(*child); }
/**
* Associate a {@link Sendable} with this Subsystem.
*
* @param child sendable
*/
void Subsystem::AddChild(Sendable* child) { AddChild(*child); }
/**
* Associate a {@link Sendable} with this Subsystem.
*
* @param child sendable
*/
void Subsystem::AddChild(Sendable& child) {
child.SetSubsystem(GetSubsystem());
LiveWindow::GetInstance()->Add(&child);
}
void Subsystem::ConfirmCommand() {
if (m_currentCommandChanged) m_currentCommandChanged = false;
}
void Subsystem::InitSendable(SendableBuilder& builder) {
builder.SetSmartDashboardType("Subsystem");

View File

@@ -9,23 +9,9 @@
using namespace frc;
/**
* Creates a new TimedCommand with the given name and timeout.
*
* @param name the name of the command
* @param timeout the time (in seconds) before this command "times out"
*/
TimedCommand::TimedCommand(const wpi::Twine& name, double timeout)
: Command(name, timeout) {}
/**
* Creates a new WaitCommand with the given timeout.
*
* @param timeout the time (in seconds) before this command "times out"
*/
TimedCommand::TimedCommand(double timeout) : Command(timeout) {}
/**
* Ends command when timed out.
*/
bool TimedCommand::IsFinished() { return IsTimedOut(); }

View File

@@ -9,19 +9,8 @@
using namespace frc;
/**
* Creates a new WaitCommand with the given name and timeout.
*
* @param name the name of the command
* @param timeout the time (in seconds) before this command "times out"
*/
WaitCommand::WaitCommand(double timeout)
: TimedCommand("Wait(" + std::to_string(timeout) + ")", timeout) {}
/**
* Creates a new WaitCommand with the given timeout.
*
* @param timeout the time (in seconds) before this command "times out"
*/
WaitCommand::WaitCommand(const wpi::Twine& name, double timeout)
: TimedCommand(name, timeout) {}

View File

@@ -11,13 +11,6 @@
using namespace frc;
/**
* A WaitCommand will wait until a certain match time before finishing.
*
* This will wait until the game clock reaches some value, then continue to the
* next command.
* @see CommandGroup
*/
WaitUntilCommand::WaitUntilCommand(double time)
: Command("WaitUntilCommand", time) {
m_time = time;
@@ -28,7 +21,4 @@ WaitUntilCommand::WaitUntilCommand(const wpi::Twine& name, double time)
m_time = time;
}
/**
* Check if we've reached the actual finish time.
*/
bool WaitUntilCommand::IsFinished() { return Timer::GetMatchTime() >= m_time; }

View File

@@ -17,11 +17,6 @@
using namespace frc;
/**
* Constructor.
*
* @param module The PCM ID to use (0-62)
*/
Compressor::Compressor(int pcmID) : m_module(pcmID) {
int32_t status = 0;
m_compressorHandle = HAL_InitializeCompressor(m_module, &status);
@@ -36,29 +31,16 @@ Compressor::Compressor(int pcmID) : m_module(pcmID) {
SetName("Compressor", pcmID);
}
/**
* Starts closed-loop control. Note that closed loop control is enabled by
* default.
*/
void Compressor::Start() {
if (StatusIsFatal()) return;
SetClosedLoopControl(true);
}
/**
* Stops closed-loop control. Note that closed loop control is enabled by
* default.
*/
void Compressor::Stop() {
if (StatusIsFatal()) return;
SetClosedLoopControl(false);
}
/**
* Check if compressor output is active.
*
* @return true if the compressor is on
*/
bool Compressor::Enabled() const {
if (StatusIsFatal()) return false;
int32_t status = 0;
@@ -73,11 +55,6 @@ bool Compressor::Enabled() const {
return value;
}
/**
* Check if the pressure switch is triggered.
*
* @return true if pressure is low
*/
bool Compressor::GetPressureSwitchValue() const {
if (StatusIsFatal()) return false;
int32_t status = 0;
@@ -92,11 +69,6 @@ bool Compressor::GetPressureSwitchValue() const {
return value;
}
/**
* Query how much current the compressor is drawing.
*
* @return The current through the compressor, in amps
*/
double Compressor::GetCompressorCurrent() const {
if (StatusIsFatal()) return 0;
int32_t status = 0;
@@ -111,13 +83,6 @@ double Compressor::GetCompressorCurrent() const {
return value;
}
/**
* Enables or disables automatically turning the compressor on when the
* pressure is low.
*
* @param on Set to true to enable closed loop control of the compressor. False
* to disable.
*/
void Compressor::SetClosedLoopControl(bool on) {
if (StatusIsFatal()) return;
int32_t status = 0;
@@ -129,13 +94,6 @@ void Compressor::SetClosedLoopControl(bool on) {
}
}
/**
* Returns true if the compressor will automatically turn on when the
* pressure is low.
*
* @return True if closed loop control of the compressor is enabled. False if
* disabled.
*/
bool Compressor::GetClosedLoopControl() const {
if (StatusIsFatal()) return false;
int32_t status = 0;
@@ -150,12 +108,6 @@ bool Compressor::GetClosedLoopControl() const {
return value;
}
/**
* Query if the compressor output has been disabled due to high current draw.
*
* @return true if PCM is in fault state : Compressor Drive is
* disabled due to compressor current being too high.
*/
bool Compressor::GetCompressorCurrentTooHighFault() const {
if (StatusIsFatal()) return false;
int32_t status = 0;
@@ -170,16 +122,6 @@ bool Compressor::GetCompressorCurrentTooHighFault() const {
return value;
}
/**
* Query if the compressor output has been disabled due to high current draw
* (sticky).
*
* A sticky fault will not clear on device reboot, it must be cleared through
* code or the webdash.
*
* @return true if PCM sticky fault is set : Compressor Drive is
* disabled due to compressor current being too high.
*/
bool Compressor::GetCompressorCurrentTooHighStickyFault() const {
if (StatusIsFatal()) return false;
int32_t status = 0;
@@ -195,16 +137,6 @@ bool Compressor::GetCompressorCurrentTooHighStickyFault() const {
return value;
}
/**
* Query if the compressor output has been disabled due to a short circuit
* (sticky).
*
* A sticky fault will not clear on device reboot, it must be cleared through
* code or the webdash.
*
* @return true if PCM sticky fault is set : Compressor output
* appears to be shorted.
*/
bool Compressor::GetCompressorShortedStickyFault() const {
if (StatusIsFatal()) return false;
int32_t status = 0;
@@ -219,12 +151,6 @@ bool Compressor::GetCompressorShortedStickyFault() const {
return value;
}
/**
* Query if the compressor output has been disabled due to a short circuit.
*
* @return true if PCM is in fault state : Compressor output
* appears to be shorted.
*/
bool Compressor::GetCompressorShortedFault() const {
if (StatusIsFatal()) return false;
int32_t status = 0;
@@ -239,15 +165,6 @@ bool Compressor::GetCompressorShortedFault() const {
return value;
}
/**
* Query if the compressor output does not appear to be wired (sticky).
*
* A sticky fault will not clear on device reboot, it must be cleared through
* code or the webdash.
*
* @return true if PCM sticky fault is set : Compressor does not
* appear to be wired, i.e. compressor is not drawing enough current.
*/
bool Compressor::GetCompressorNotConnectedStickyFault() const {
if (StatusIsFatal()) return false;
int32_t status = 0;
@@ -262,12 +179,6 @@ bool Compressor::GetCompressorNotConnectedStickyFault() const {
return value;
}
/**
* Query if the compressor output does not appear to be wired.
*
* @return true if PCM is in fault state : Compressor does not
* appear to be wired, i.e. compressor is not drawing enough current.
*/
bool Compressor::GetCompressorNotConnectedFault() const {
if (StatusIsFatal()) return false;
int32_t status = 0;
@@ -282,16 +193,6 @@ bool Compressor::GetCompressorNotConnectedFault() const {
return value;
}
/**
* Clear ALL sticky faults inside PCM that Compressor is wired to.
*
* If a sticky fault is set, then it will be persistently cleared. Compressor
* drive maybe momentarily disable while flags are being cleared. Care should
* be taken to not call this too frequently, otherwise normal compressor
* functionality may be prevented.
*
* If no sticky faults are set then this call will have no effect.
*/
void Compressor::ClearAllPCMStickyFaults() {
if (StatusIsFatal()) return;
int32_t status = 0;

View File

@@ -16,12 +16,6 @@
using namespace frc;
/**
* Get the input voltage to the robot controller.
*
* @return The controller input voltage value in Volts
* @deprecated Use RobotController static class method
*/
double ControllerPower::GetInputVoltage() {
int32_t status = 0;
double retVal = HAL_GetVinVoltage(&status);
@@ -29,12 +23,6 @@ double ControllerPower::GetInputVoltage() {
return retVal;
}
/**
* Get the input current to the robot controller.
*
* @return The controller input current value in Amps
* @deprecated Use RobotController static class method
*/
double ControllerPower::GetInputCurrent() {
int32_t status = 0;
double retVal = HAL_GetVinCurrent(&status);
@@ -42,120 +30,6 @@ double ControllerPower::GetInputCurrent() {
return retVal;
}
/**
* Get the voltage of the 6V rail.
*
* @return The controller 6V rail voltage value in Volts
* @deprecated Use RobotController static class method
*/
double ControllerPower::GetVoltage6V() {
int32_t status = 0;
double retVal = HAL_GetUserVoltage6V(&status);
wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
return retVal;
}
/**
* Get the current output of the 6V rail.
*
* @return The controller 6V rail output current value in Amps
* @deprecated Use RobotController static class method
*/
double ControllerPower::GetCurrent6V() {
int32_t status = 0;
double retVal = HAL_GetUserCurrent6V(&status);
wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
return retVal;
}
/**
* Get the enabled state of the 6V rail. The rail may be disabled due to a
* controller brownout, a short circuit on the rail, or controller over-voltage.
*
* @return The controller 6V rail enabled value. True for enabled.
* @deprecated Use RobotController static class method
*/
bool ControllerPower::GetEnabled6V() {
int32_t status = 0;
bool retVal = HAL_GetUserActive6V(&status);
wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
return retVal;
}
/**
* Get the count of the total current faults on the 6V rail since the controller
* has booted.
*
* @return The number of faults.
* @deprecated Use RobotController static class method
*/
int ControllerPower::GetFaultCount6V() {
int32_t status = 0;
int retVal = HAL_GetUserCurrentFaults6V(&status);
wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
return retVal;
}
/**
* Get the voltage of the 5V rail.
*
* @return The controller 5V rail voltage value in Volts
* @deprecated Use RobotController static class method
*/
double ControllerPower::GetVoltage5V() {
int32_t status = 0;
double retVal = HAL_GetUserVoltage5V(&status);
wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
return retVal;
}
/**
* Get the current output of the 5V rail.
*
* @return The controller 5V rail output current value in Amps
* @deprecated Use RobotController static class method
*/
double ControllerPower::GetCurrent5V() {
int32_t status = 0;
double retVal = HAL_GetUserCurrent5V(&status);
wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
return retVal;
}
/**
* Get the enabled state of the 5V rail. The rail may be disabled due to a
* controller brownout, a short circuit on the rail, or controller over-voltage.
*
* @return The controller 5V rail enabled value. True for enabled.
* @deprecated Use RobotController static class method
*/
bool ControllerPower::GetEnabled5V() {
int32_t status = 0;
bool retVal = HAL_GetUserActive5V(&status);
wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
return retVal;
}
/**
* Get the count of the total current faults on the 5V rail since the controller
* has booted.
*
* @return The number of faults
* @deprecated Use RobotController static class method
*/
int ControllerPower::GetFaultCount5V() {
int32_t status = 0;
int retVal = HAL_GetUserCurrentFaults5V(&status);
wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
return retVal;
}
/**
* Get the voltage of the 3.3V rail.
*
* @return The controller 3.3V rail voltage value in Volts
* @deprecated Use RobotController static class method
*/
double ControllerPower::GetVoltage3V3() {
int32_t status = 0;
double retVal = HAL_GetUserVoltage3V3(&status);
@@ -163,12 +37,6 @@ double ControllerPower::GetVoltage3V3() {
return retVal;
}
/**
* Get the current output of the 3.3V rail.
*
* @return The controller 3.3V rail output current value in Amps
* @deprecated Use RobotController static class method
*/
double ControllerPower::GetCurrent3V3() {
int32_t status = 0;
double retVal = HAL_GetUserCurrent3V3(&status);
@@ -176,13 +44,6 @@ double ControllerPower::GetCurrent3V3() {
return retVal;
}
/**
* Get the enabled state of the 3.3V rail. The rail may be disabled due to a
* controller brownout, a short circuit on the rail, or controller over-voltage.
*
* @return The controller 3.3V rail enabled value. True for enabled.
* @deprecated Use RobotController static class method
*/
bool ControllerPower::GetEnabled3V3() {
int32_t status = 0;
bool retVal = HAL_GetUserActive3V3(&status);
@@ -190,16 +51,65 @@ bool ControllerPower::GetEnabled3V3() {
return retVal;
}
/**
* Get the count of the total current faults on the 3.3V rail since the
* controller has booted.
*
* @return The number of faults
* @deprecated Use RobotController static class method
*/
int ControllerPower::GetFaultCount3V3() {
int32_t status = 0;
int retVal = HAL_GetUserCurrentFaults3V3(&status);
wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
return retVal;
}
double ControllerPower::GetVoltage5V() {
int32_t status = 0;
double retVal = HAL_GetUserVoltage5V(&status);
wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
return retVal;
}
double ControllerPower::GetCurrent5V() {
int32_t status = 0;
double retVal = HAL_GetUserCurrent5V(&status);
wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
return retVal;
}
bool ControllerPower::GetEnabled5V() {
int32_t status = 0;
bool retVal = HAL_GetUserActive5V(&status);
wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
return retVal;
}
int ControllerPower::GetFaultCount5V() {
int32_t status = 0;
int retVal = HAL_GetUserCurrentFaults5V(&status);
wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
return retVal;
}
double ControllerPower::GetVoltage6V() {
int32_t status = 0;
double retVal = HAL_GetUserVoltage6V(&status);
wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
return retVal;
}
double ControllerPower::GetCurrent6V() {
int32_t status = 0;
double retVal = HAL_GetUserCurrent6V(&status);
wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
return retVal;
}
bool ControllerPower::GetEnabled6V() {
int32_t status = 0;
bool retVal = HAL_GetUserActive6V(&status);
wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
return retVal;
}
int ControllerPower::GetFaultCount6V() {
int32_t status = 0;
int retVal = HAL_GetUserCurrentFaults6V(&status);
wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
return retVal;
}

View File

@@ -16,19 +16,6 @@
using namespace frc;
/**
* Create an instance of a counter where no sources are selected.
*
* They all must be selected by calling functions to specify the upsource and
* the downsource independently.
*
* This creates a ChipObject counter and initializes status variables
* appropriately.
*
* The counter will start counting immediately.
*
* @param mode The counter mode
*/
Counter::Counter(Mode mode) {
int32_t status = 0;
m_counter = HAL_InitializeCounter((HAL_Counter_Mode)mode, &m_index, &status);
@@ -40,82 +27,26 @@ Counter::Counter(Mode mode) {
SetName("Counter", m_index);
}
/**
* Create an instance of a counter from a Digital Source (such as a Digital
* Input).
*
* This is used if an existing digital input is to be shared by multiple other
* objects such as encoders or if the Digital Source is not a Digital Input
* channel (such as an Analog Trigger).
*
* The counter will start counting immediately.
* @param source A pointer to the existing DigitalSource object. It will be set
* as the Up Source.
*/
Counter::Counter(DigitalSource* source) : Counter(kTwoPulse) {
SetUpSource(source);
ClearDownSource();
}
/**
* Create an instance of a counter from a Digital Source (such as a Digital
* Input).
*
* This is used if an existing digital input is to be shared by multiple other
* objects such as encoders or if the Digital Source is not a Digital Input
* channel (such as an Analog Trigger).
*
* The counter will start counting immediately.
*
* @param source A pointer to the existing DigitalSource object. It will be
* set as the Up Source.
*/
Counter::Counter(std::shared_ptr<DigitalSource> source) : Counter(kTwoPulse) {
SetUpSource(source);
ClearDownSource();
}
/**
* Create an instance of a Counter object.
*
* Create an up-Counter instance given a channel.
*
* The counter will start counting immediately.
*
* @param channel The DIO channel to use as the up source. 0-9 are on-board,
* 10-25 are on the MXP
*/
Counter::Counter(int channel) : Counter(kTwoPulse) {
SetUpSource(channel);
ClearDownSource();
}
/**
* Create an instance of a Counter object.
*
* Create an instance of a simple up-Counter given an analog trigger.
* Use the trigger state output from the analog trigger.
*
* The counter will start counting immediately.
*
* @param trigger The reference to the existing AnalogTrigger object.
*/
Counter::Counter(DigitalSource* source) : Counter(kTwoPulse) {
SetUpSource(source);
ClearDownSource();
}
Counter::Counter(std::shared_ptr<DigitalSource> source) : Counter(kTwoPulse) {
SetUpSource(source);
ClearDownSource();
}
Counter::Counter(const AnalogTrigger& trigger) : Counter(kTwoPulse) {
SetUpSource(trigger.CreateOutput(AnalogTriggerType::kState));
ClearDownSource();
}
/**
* Create an instance of a Counter object.
*
* Creates a full up-down counter given two Digital Sources.
*
* @param encodingType The quadrature decoding mode (1x or 2x)
* @param upSource The pointer to the DigitalSource to set as the up source
* @param downSource The pointer to the DigitalSource to set as the down
* source
* @param inverted True to invert the output (reverse the direction)
*/
Counter::Counter(EncodingType encodingType, DigitalSource* upSource,
DigitalSource* downSource, bool inverted)
: Counter(encodingType,
@@ -125,17 +56,6 @@ Counter::Counter(EncodingType encodingType, DigitalSource* upSource,
NullDeleter<DigitalSource>()),
inverted) {}
/**
* Create an instance of a Counter object.
*
* Creates a full up-down counter given two Digital Sources.
*
* @param encodingType The quadrature decoding mode (1x or 2x)
* @param upSource The pointer to the DigitalSource to set as the up source
* @param downSource The pointer to the DigitalSource to set as the down
* source
* @param inverted True to invert the output (reverse the direction)
*/
Counter::Counter(EncodingType encodingType,
std::shared_ptr<DigitalSource> upSource,
std::shared_ptr<DigitalSource> downSource, bool inverted)
@@ -162,9 +82,6 @@ Counter::Counter(EncodingType encodingType,
SetDownSourceEdge(inverted, true);
}
/**
* Delete the Counter object.
*/
Counter::~Counter() {
SetUpdateWhenEmpty(true);
@@ -174,24 +91,12 @@ Counter::~Counter() {
m_counter = HAL_kInvalidHandle;
}
/**
* Set the upsource for the counter as a digital input channel.
*
* @param channel The DIO channel to use as the up source. 0-9 are on-board,
* 10-25 are on the MXP
*/
void Counter::SetUpSource(int channel) {
if (StatusIsFatal()) return;
SetUpSource(std::make_shared<DigitalInput>(channel));
AddChild(m_upSource);
}
/**
* Set the up counting source to be an analog trigger.
*
* @param analogTrigger The analog trigger object that is used for the Up Source
* @param triggerType The analog trigger output that will trigger the counter.
*/
void Counter::SetUpSource(AnalogTrigger* analogTrigger,
AnalogTriggerType triggerType) {
SetUpSource(std::shared_ptr<AnalogTrigger>(analogTrigger,
@@ -199,25 +104,17 @@ void Counter::SetUpSource(AnalogTrigger* analogTrigger,
triggerType);
}
/**
* Set the up counting source to be an analog trigger.
*
* @param analogTrigger The analog trigger object that is used for the Up Source
* @param triggerType The analog trigger output that will trigger the counter.
*/
void Counter::SetUpSource(std::shared_ptr<AnalogTrigger> analogTrigger,
AnalogTriggerType triggerType) {
if (StatusIsFatal()) return;
SetUpSource(analogTrigger->CreateOutput(triggerType));
}
/**
* Set the source object that causes the counter to count up.
*
* Set the up counting DigitalSource.
*
* @param source Pointer to the DigitalSource object to set as the up source
*/
void Counter::SetUpSource(DigitalSource* source) {
SetUpSource(
std::shared_ptr<DigitalSource>(source, NullDeleter<DigitalSource>()));
}
void Counter::SetUpSource(std::shared_ptr<DigitalSource> source) {
if (StatusIsFatal()) return;
m_upSource = source;
@@ -233,31 +130,11 @@ void Counter::SetUpSource(std::shared_ptr<DigitalSource> source) {
}
}
void Counter::SetUpSource(DigitalSource* source) {
SetUpSource(
std::shared_ptr<DigitalSource>(source, NullDeleter<DigitalSource>()));
}
/**
* Set the source object that causes the counter to count up.
*
* Set the up counting DigitalSource.
*
* @param source Reference to the DigitalSource object to set as the up source
*/
void Counter::SetUpSource(DigitalSource& source) {
SetUpSource(
std::shared_ptr<DigitalSource>(&source, NullDeleter<DigitalSource>()));
}
/**
* Set the edge sensitivity on an up counting source.
*
* Set the up source to either detect rising edges or falling edges or both.
*
* @param risingEdge True to trigger on rising edges
* @param fallingEdge True to trigger on falling edges
*/
void Counter::SetUpSourceEdge(bool risingEdge, bool fallingEdge) {
if (StatusIsFatal()) return;
if (m_upSource == nullptr) {
@@ -270,9 +147,6 @@ void Counter::SetUpSourceEdge(bool risingEdge, bool fallingEdge) {
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Disable the up counting source to the counter.
*/
void Counter::ClearUpSource() {
if (StatusIsFatal()) return;
m_upSource.reset();
@@ -281,25 +155,12 @@ void Counter::ClearUpSource() {
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Set the down counting source to be a digital input channel.
*
* @param channel The DIO channel to use as the up source. 0-9 are on-board,
* 10-25 are on the MXP
*/
void Counter::SetDownSource(int channel) {
if (StatusIsFatal()) return;
SetDownSource(std::make_shared<DigitalInput>(channel));
AddChild(m_downSource);
}
/**
* Set the down counting source to be an analog trigger.
*
* @param analogTrigger The analog trigger object that is used for the Down
* Source
* @param triggerType The analog trigger output that will trigger the counter.
*/
void Counter::SetDownSource(AnalogTrigger* analogTrigger,
AnalogTriggerType triggerType) {
SetDownSource(std::shared_ptr<AnalogTrigger>(analogTrigger,
@@ -307,26 +168,22 @@ void Counter::SetDownSource(AnalogTrigger* analogTrigger,
triggerType);
}
/**
* Set the down counting source to be an analog trigger.
*
* @param analogTrigger The analog trigger object that is used for the Down
* Source
* @param triggerType The analog trigger output that will trigger the counter.
*/
void Counter::SetDownSource(std::shared_ptr<AnalogTrigger> analogTrigger,
AnalogTriggerType triggerType) {
if (StatusIsFatal()) return;
SetDownSource(analogTrigger->CreateOutput(triggerType));
}
/**
* Set the source object that causes the counter to count down.
*
* Set the down counting DigitalSource.
*
* @param source Pointer to the DigitalSource object to set as the down source
*/
void Counter::SetDownSource(DigitalSource* source) {
SetDownSource(
std::shared_ptr<DigitalSource>(source, NullDeleter<DigitalSource>()));
}
void Counter::SetDownSource(DigitalSource& source) {
SetDownSource(
std::shared_ptr<DigitalSource>(&source, NullDeleter<DigitalSource>()));
}
void Counter::SetDownSource(std::shared_ptr<DigitalSource> source) {
if (StatusIsFatal()) return;
m_downSource = source;
@@ -342,31 +199,6 @@ void Counter::SetDownSource(std::shared_ptr<DigitalSource> source) {
}
}
void Counter::SetDownSource(DigitalSource* source) {
SetDownSource(
std::shared_ptr<DigitalSource>(source, NullDeleter<DigitalSource>()));
}
/**
* Set the source object that causes the counter to count down.
*
* Set the down counting DigitalSource.
*
* @param source Reference to the DigitalSource object to set as the down source
*/
void Counter::SetDownSource(DigitalSource& source) {
SetDownSource(
std::shared_ptr<DigitalSource>(&source, NullDeleter<DigitalSource>()));
}
/**
* Set the edge sensitivity on a down counting source.
*
* Set the down source to either detect rising edges or falling edges.
*
* @param risingEdge True to trigger on rising edges
* @param fallingEdge True to trigger on falling edges
*/
void Counter::SetDownSourceEdge(bool risingEdge, bool fallingEdge) {
if (StatusIsFatal()) return;
if (m_downSource == nullptr) {
@@ -379,9 +211,6 @@ void Counter::SetDownSourceEdge(bool risingEdge, bool fallingEdge) {
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Disable the down counting source to the counter.
*/
void Counter::ClearDownSource() {
if (StatusIsFatal()) return;
m_downSource.reset();
@@ -390,11 +219,6 @@ void Counter::ClearDownSource() {
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Set standard up / down counting mode on this counter.
*
* Up and down counts are sourced independently from two inputs.
*/
void Counter::SetUpDownCounterMode() {
if (StatusIsFatal()) return;
int32_t status = 0;
@@ -402,12 +226,6 @@ void Counter::SetUpDownCounterMode() {
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Set external direction mode on this counter.
*
* Counts are sourced on the Up counter input.
* The Down counter input represents the direction to count.
*/
void Counter::SetExternalDirectionMode() {
if (StatusIsFatal()) return;
int32_t status = 0;
@@ -415,11 +233,6 @@ void Counter::SetExternalDirectionMode() {
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Set Semi-period mode on this counter.
*
* Counts up on both rising and falling edges.
*/
void Counter::SetSemiPeriodMode(bool highSemiPeriod) {
if (StatusIsFatal()) return;
int32_t status = 0;
@@ -427,15 +240,6 @@ void Counter::SetSemiPeriodMode(bool highSemiPeriod) {
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Configure the counter to count in up or down based on the length of the input
* pulse.
*
* This mode is most useful for direction sensitive gear tooth sensors.
*
* @param threshold The pulse length beyond which the counter counts the
* opposite direction. Units are seconds.
*/
void Counter::SetPulseLengthMode(double threshold) {
if (StatusIsFatal()) return;
int32_t status = 0;
@@ -443,29 +247,13 @@ void Counter::SetPulseLengthMode(double threshold) {
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Get the Samples to Average which specifies the number of samples of the timer
* to average when calculating the period.
*
* Perform averaging to account for mechanical imperfections or as oversampling
* to increase resolution.
*
* @return The number of samples being averaged (from 1 to 127)
*/
int Counter::GetSamplesToAverage() const {
void Counter::SetReverseDirection(bool reverseDirection) {
if (StatusIsFatal()) return;
int32_t status = 0;
int samples = HAL_GetCounterSamplesToAverage(m_counter, &status);
HAL_SetCounterReverseDirection(m_counter, reverseDirection, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
return samples;
}
/**
* Set the Samples to Average which specifies the number of samples of the timer
* to average when calculating the period. Perform averaging to account for
* mechanical imperfections or as oversampling to increase resolution.
*
* @param samplesToAverage The number of samples to average from 1 to 127.
*/
void Counter::SetSamplesToAverage(int samplesToAverage) {
if (samplesToAverage < 1 || samplesToAverage > 127) {
wpi_setWPIErrorWithContext(
@@ -477,12 +265,15 @@ void Counter::SetSamplesToAverage(int samplesToAverage) {
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Read the current counter value.
*
* Read the value at this instant. It may still be running, so it reflects the
* current value. Next time it is read, it might have a different value.
*/
int Counter::GetSamplesToAverage() const {
int32_t status = 0;
int samples = HAL_GetCounterSamplesToAverage(m_counter, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
return samples;
}
int Counter::GetFPGAIndex() const { return m_index; }
int Counter::Get() const {
if (StatusIsFatal()) return 0;
int32_t status = 0;
@@ -491,12 +282,6 @@ int Counter::Get() const {
return value;
}
/**
* Reset the Counter to zero.
*
* Set the counter value to zero. This doesn't effect the running state of the
* counter, just sets the current value to zero.
*/
void Counter::Reset() {
if (StatusIsFatal()) return;
int32_t status = 0;
@@ -504,14 +289,6 @@ void Counter::Reset() {
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Get the Period of the most recent count.
*
* Returns the time interval of the most recent count. This can be used for
* velocity calculations to determine shaft speed.
*
* @returns The period between the last two pulses in units of seconds.
*/
double Counter::GetPeriod() const {
if (StatusIsFatal()) return 0.0;
int32_t status = 0;
@@ -520,16 +297,6 @@ double Counter::GetPeriod() const {
return value;
}
/**
* Set the maximum period where the device is still considered "moving".
*
* Sets the maximum period where the device is considered moving. This value is
* used to determine the "stopped" state of the counter using the GetStopped
* method.
*
* @param maxPeriod The maximum period where the counted device is considered
* moving in seconds.
*/
void Counter::SetMaxPeriod(double maxPeriod) {
if (StatusIsFatal()) return;
int32_t status = 0;
@@ -537,23 +304,6 @@ void Counter::SetMaxPeriod(double maxPeriod) {
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Select whether you want to continue updating the event timer output when
* there are no samples captured.
*
* The output of the event timer has a buffer of periods that are averaged and
* posted to a register on the FPGA. When the timer detects that the event
* source has stopped (based on the MaxPeriod) the buffer of samples to be
* averaged is emptied. If you enable the update when empty, you will be
* notified of the stopped source and the event time will report 0 samples.
* If you disable update when empty, the most recent average will remain on
* the output until a new sample is acquired. You will never see 0 samples
* output (except when there have been no events since an FPGA reset) and you
* will likely not see the stopped bit become true (since it is updated at the
* end of an average and there are no samples to average).
*
* @param enabled True to enable update when empty
*/
void Counter::SetUpdateWhenEmpty(bool enabled) {
if (StatusIsFatal()) return;
int32_t status = 0;
@@ -561,16 +311,6 @@ void Counter::SetUpdateWhenEmpty(bool enabled) {
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Determine if the clock is stopped.
*
* Determine if the clocked input is stopped based on the MaxPeriod value set
* using the SetMaxPeriod method. If the clock exceeds the MaxPeriod, then the
* device (and counter) are assumed to be stopped and it returns true.
*
* @return Returns true if the most recent counter period exceeds the MaxPeriod
* value set by SetMaxPeriod.
*/
bool Counter::GetStopped() const {
if (StatusIsFatal()) return false;
int32_t status = 0;
@@ -579,11 +319,6 @@ bool Counter::GetStopped() const {
return value;
}
/**
* The last direction the counter value changed.
*
* @return The last direction the counter value changed.
*/
bool Counter::GetDirection() const {
if (StatusIsFatal()) return false;
int32_t status = 0;
@@ -592,21 +327,6 @@ bool Counter::GetDirection() const {
return value;
}
/**
* Set the Counter to return reversed sensing on the direction.
*
* This allows counters to change the direction they are counting in the case of
* 1X and 2X quadrature encoding only. Any other counter mode isn't supported.
*
* @param reverseDirection true if the value counted should be negated.
*/
void Counter::SetReverseDirection(bool reverseDirection) {
if (StatusIsFatal()) return;
int32_t status = 0;
HAL_SetCounterReverseDirection(m_counter, reverseDirection, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
void Counter::InitSendable(SendableBuilder& builder) {
builder.SetSmartDashboardType("Counter");
builder.AddDoubleProperty("Value", [=]() { return Get(); }, nullptr);

View File

@@ -11,14 +11,8 @@
using namespace frc;
/**
* Constructor for a Digilent DMC 60.
*
* @param channel The PWM channel that the DMC 60 is attached to. 0-9 are
* on-board, 10-19 are on the MXP port
*/
DMC60::DMC60(int channel) : PWMSpeedController(channel) {
/**
/*
* Note that the DMC 60 uses the following bounds for PWM values. These
* values should work reasonably well for most controllers, but if users
* experience issues such as asymmetric behavior around the deadband or

View File

@@ -46,11 +46,6 @@ DigitalGlitchFilter::~DigitalGlitchFilter() {
}
}
/**
* Assigns the DigitalSource to this glitch filter.
*
* @param input The DigitalSource to add.
*/
void DigitalGlitchFilter::Add(DigitalSource* input) {
DoAdd(input, m_channelIndex + 1);
}
@@ -80,11 +75,6 @@ void DigitalGlitchFilter::DoAdd(DigitalSource* input, int requestedIndex) {
}
}
/**
* Assigns the Encoder to this glitch filter.
*
* @param input The Encoder to add.
*/
void DigitalGlitchFilter::Add(Encoder* input) {
Add(input->m_aSource.get());
if (StatusIsFatal()) {
@@ -93,11 +83,6 @@ void DigitalGlitchFilter::Add(Encoder* input) {
Add(input->m_bSource.get());
}
/**
* Assigns the Counter to this glitch filter.
*
* @param input The Counter to add.
*/
void DigitalGlitchFilter::Add(Counter* input) {
Add(input->m_upSource.get());
if (StatusIsFatal()) {
@@ -106,24 +91,8 @@ void DigitalGlitchFilter::Add(Counter* input) {
Add(input->m_downSource.get());
}
/**
* Removes a digital input from this filter.
*
* Removes the DigitalSource from this glitch filter and re-assigns it to
* the default filter.
*
* @param input The DigitalSource to remove.
*/
void DigitalGlitchFilter::Remove(DigitalSource* input) { DoAdd(input, 0); }
/**
* Removes an encoder from this filter.
*
* Removes the Encoder from this glitch filter and re-assigns it to
* the default filter.
*
* @param input The Encoder to remove.
*/
void DigitalGlitchFilter::Remove(Encoder* input) {
Remove(input->m_aSource.get());
if (StatusIsFatal()) {
@@ -132,14 +101,6 @@ void DigitalGlitchFilter::Remove(Encoder* input) {
Remove(input->m_bSource.get());
}
/**
* Removes a counter from this filter.
*
* Removes the Counter from this glitch filter and re-assigns it to
* the default filter.
*
* @param input The Counter to remove.
*/
void DigitalGlitchFilter::Remove(Counter* input) {
Remove(input->m_upSource.get());
if (StatusIsFatal()) {
@@ -148,22 +109,12 @@ void DigitalGlitchFilter::Remove(Counter* input) {
Remove(input->m_downSource.get());
}
/**
* Sets the number of cycles that the input must not change state for.
*
* @param fpgaCycles The number of FPGA cycles.
*/
void DigitalGlitchFilter::SetPeriodCycles(int fpgaCycles) {
int32_t status = 0;
HAL_SetFilterPeriod(m_channelIndex, fpgaCycles, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Sets the number of nanoseconds that the input must not change state for.
*
* @param nanoseconds The number of nanoseconds.
*/
void DigitalGlitchFilter::SetPeriodNanoSeconds(uint64_t nanoseconds) {
int32_t status = 0;
int fpgaCycles =
@@ -173,11 +124,6 @@ void DigitalGlitchFilter::SetPeriodNanoSeconds(uint64_t nanoseconds) {
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Gets the number of cycles that the input must not change state for.
*
* @return The number of cycles.
*/
int DigitalGlitchFilter::GetPeriodCycles() {
int32_t status = 0;
int fpgaCycles = HAL_GetFilterPeriod(m_channelIndex, &status);
@@ -187,11 +133,6 @@ int DigitalGlitchFilter::GetPeriodCycles() {
return fpgaCycles;
}
/**
* Gets the number of nanoseconds that the input must not change state for.
*
* @return The number of nanoseconds.
*/
uint64_t DigitalGlitchFilter::GetPeriodNanoSeconds() {
int32_t status = 0;
int fpgaCycles = HAL_GetFilterPeriod(m_channelIndex, &status);

View File

@@ -19,13 +19,6 @@
using namespace frc;
/**
* Create an instance of a Digital Input class.
*
* Creates a digital input given a channel.
*
* @param channel The DIO channel 0-9 are on-board, 10-25 are on the MXP port
*/
DigitalInput::DigitalInput(int channel) {
if (!SensorUtil::CheckDigitalChannel(channel)) {
wpi_setWPIErrorWithContext(ChannelIndexOutOfRange,
@@ -49,9 +42,6 @@ DigitalInput::DigitalInput(int channel) {
SetName("DigitalInput", channel);
}
/**
* Free resources associated with the Digital Input class.
*/
DigitalInput::~DigitalInput() {
if (StatusIsFatal()) return;
if (m_interrupt != HAL_kInvalidHandle) {
@@ -64,11 +54,6 @@ DigitalInput::~DigitalInput() {
HAL_FreeDIOPort(m_handle);
}
/**
* Get the value from a digital input channel.
*
* Retrieve the value of a single digital input channel from the FPGA.
*/
bool DigitalInput::Get() const {
if (StatusIsFatal()) return false;
int32_t status = 0;
@@ -77,28 +62,16 @@ bool DigitalInput::Get() const {
return value;
}
/**
* @return The GPIO channel number that this object represents.
*/
int DigitalInput::GetChannel() const { return m_channel; }
/**
* @return The HAL Handle to the specified source.
*/
HAL_Handle DigitalInput::GetPortHandleForRouting() const { return m_handle; }
/**
* Is source an AnalogTrigger
*/
bool DigitalInput::IsAnalogTrigger() const { return false; }
/**
* @return The type of analog trigger output to be used. 0 for Digitals
*/
AnalogTriggerType DigitalInput::GetAnalogTriggerTypeForRouting() const {
return (AnalogTriggerType)0;
}
bool DigitalInput::IsAnalogTrigger() const { return false; }
int DigitalInput::GetChannel() const { return m_channel; }
void DigitalInput::InitSendable(SendableBuilder& builder) {
builder.SetSmartDashboardType("Digital Input");
builder.AddBooleanProperty("Value", [=]() { return Get(); }, nullptr);

View File

@@ -19,14 +19,6 @@
using namespace frc;
/**
* Create an instance of a digital output.
*
* Create a digital output given a channel.
*
* @param channel The digital channel 0-9 are on-board, 10-25 are on the MXP
* port
*/
DigitalOutput::DigitalOutput(int channel) {
m_pwmGenerator = HAL_kInvalidHandle;
if (!SensorUtil::CheckDigitalChannel(channel)) {
@@ -51,9 +43,6 @@ DigitalOutput::DigitalOutput(int channel) {
SetName("DigitalOutput", channel);
}
/**
* Free the resources associated with a digital output.
*/
DigitalOutput::~DigitalOutput() {
if (StatusIsFatal()) return;
// Disable the PWM in case it was running.
@@ -62,13 +51,6 @@ DigitalOutput::~DigitalOutput() {
HAL_FreeDIOPort(m_handle);
}
/**
* Set the value of a digital output.
*
* Set the value of a digital output to either one (true) or zero (false).
*
* @param value 1 (true) for high, 0 (false) for disabled
*/
void DigitalOutput::Set(bool value) {
if (StatusIsFatal()) return;
@@ -77,11 +59,6 @@ void DigitalOutput::Set(bool value) {
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Gets the value being output from the Digital Output.
*
* @return the state of the digital output.
*/
bool DigitalOutput::Get() const {
if (StatusIsFatal()) return false;
@@ -91,19 +68,8 @@ bool DigitalOutput::Get() const {
return val;
}
/**
* @return The GPIO channel number that this object represents.
*/
int DigitalOutput::GetChannel() const { return m_channel; }
/**
* Output a single pulse on the digital output line.
*
* Send a single pulse on the digital output line where the pulse duration is
* specified in seconds. Maximum pulse length is 0.0016 seconds.
*
* @param length The pulse length in seconds
*/
void DigitalOutput::Pulse(double length) {
if (StatusIsFatal()) return;
@@ -112,11 +78,6 @@ void DigitalOutput::Pulse(double length) {
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Determine if the pulse is still going.
*
* Determine if a previously started pulse is still going.
*/
bool DigitalOutput::IsPulsing() const {
if (StatusIsFatal()) return false;
@@ -126,16 +87,6 @@ bool DigitalOutput::IsPulsing() const {
return value;
}
/**
* Change the PWM frequency of the PWM output on a Digital Output line.
*
* The valid range is from 0.6 Hz to 19 kHz. The frequency resolution is
* logarithmic.
*
* There is only one PWM frequency for all digital channels.
*
* @param rate The frequency to output all digital output PWM signals.
*/
void DigitalOutput::SetPWMRate(double rate) {
if (StatusIsFatal()) return;
@@ -144,19 +95,6 @@ void DigitalOutput::SetPWMRate(double rate) {
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Enable a PWM Output on this line.
*
* Allocate one of the 6 DO PWM generator resources from this module.
*
* Supply the initial duty-cycle to output so as to avoid a glitch when first
* starting.
*
* The resolution of the duty cycle is 8-bit for low frequencies (1kHz or less)
* but is reduced the higher the frequency of the PWM signal is.
*
* @param initialDutyCycle The duty-cycle to start generating. [0..1]
*/
void DigitalOutput::EnablePWM(double initialDutyCycle) {
if (m_pwmGenerator != HAL_kInvalidHandle) return;
@@ -175,11 +113,6 @@ void DigitalOutput::EnablePWM(double initialDutyCycle) {
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Change this line from a PWM output back to a static Digital Output line.
*
* Free up one of the 6 DO PWM generator resources that were in use.
*/
void DigitalOutput::DisablePWM() {
if (StatusIsFatal()) return;
if (m_pwmGenerator == HAL_kInvalidHandle) return;
@@ -197,14 +130,6 @@ void DigitalOutput::DisablePWM() {
m_pwmGenerator = HAL_kInvalidHandle;
}
/**
* Change the duty-cycle that is being generated on the line.
*
* The resolution of the duty cycle is 8-bit for low frequencies (1kHz or less)
* but is reduced the higher the frequency of the PWM signal is.
*
* @param dutyCycle The duty-cycle to change to. [0..1]
*/
void DigitalOutput::UpdateDutyCycle(double dutyCycle) {
if (StatusIsFatal()) return;

View File

@@ -17,25 +17,10 @@
using namespace frc;
/**
* Constructor.
*
* Uses the default PCM ID of 0.
*
* @param forwardChannel The forward channel number on the PCM (0..7).
* @param reverseChannel The reverse channel number on the PCM (0..7).
*/
DoubleSolenoid::DoubleSolenoid(int forwardChannel, int reverseChannel)
: DoubleSolenoid(SensorUtil::GetDefaultSolenoidModule(), forwardChannel,
reverseChannel) {}
/**
* Constructor.
*
* @param moduleNumber The CAN ID of the PCM.
* @param forwardChannel The forward channel on the PCM to control (0..7).
* @param reverseChannel The reverse channel on the PCM to control (0..7).
*/
DoubleSolenoid::DoubleSolenoid(int moduleNumber, int forwardChannel,
int reverseChannel)
: SolenoidBase(moduleNumber),
@@ -91,19 +76,11 @@ DoubleSolenoid::DoubleSolenoid(int moduleNumber, int forwardChannel,
SetName("DoubleSolenoid", m_moduleNumber, m_forwardChannel);
}
/**
* Destructor.
*/
DoubleSolenoid::~DoubleSolenoid() {
HAL_FreeSolenoidPort(m_forwardHandle);
HAL_FreeSolenoidPort(m_reverseHandle);
}
/**
* Set the value of a solenoid.
*
* @param value The value to set (Off, Forward or Reverse)
*/
void DoubleSolenoid::Set(Value value) {
if (StatusIsFatal()) return;
@@ -132,11 +109,6 @@ void DoubleSolenoid::Set(Value value) {
wpi_setErrorWithContext(rstatus, HAL_GetErrorMessage(rstatus));
}
/**
* Read the current value of the solenoid.
*
* @return The current value of the solenoid.
*/
DoubleSolenoid::Value DoubleSolenoid::Get() const {
if (StatusIsFatal()) return kOff;
int fstatus = 0;
@@ -152,29 +124,11 @@ DoubleSolenoid::Value DoubleSolenoid::Get() const {
return kOff;
}
/**
* Check if the forward solenoid is blacklisted.
*
* If a solenoid is shorted, it is added to the blacklist and
* disabled until power cycle, or until faults are cleared.
* @see ClearAllPCMStickyFaults()
*
* @return If solenoid is disabled due to short.
*/
bool DoubleSolenoid::IsFwdSolenoidBlackListed() const {
int blackList = GetPCMSolenoidBlackList(m_moduleNumber);
return (blackList & m_forwardMask) != 0;
}
/**
* Check if the reverse solenoid is blacklisted.
*
* If a solenoid is shorted, it is added to the blacklist and
* disabled until power cycle, or until faults are cleared.
*
* @see ClearAllPCMStickyFaults()
* @return If solenoid is disabled due to short.
*/
bool DoubleSolenoid::IsRevSolenoidBlackListed() const {
int blackList = GetPCMSolenoidBlackList(m_moduleNumber);
return (blackList & m_reverseMask) != 0;

View File

@@ -17,12 +17,6 @@
using namespace frc;
/**
* Construct a DifferentialDrive.
*
* To pass multiple motors per side, use a SpeedControllerGroup. If a motor
* needs to be inverted, do so before passing it in.
*/
DifferentialDrive::DifferentialDrive(SpeedController& leftMotor,
SpeedController& rightMotor)
: m_leftMotor(leftMotor), m_rightMotor(rightMotor) {
@@ -33,18 +27,6 @@ DifferentialDrive::DifferentialDrive(SpeedController& leftMotor,
SetName("DifferentialDrive", instances);
}
/**
* Arcade drive method for differential drive platform.
*
* Note: Some drivers may prefer inverted rotation controls. This can be done by
* negating the value passed for rotation.
*
* @param xSpeed The speed at which the robot should drive along the X
* axis [-1.0..1.0]. Forward is negative.
* @param zRotation The rotation rate of the robot around the Z axis
* [-1.0..1.0]. Clockwise is positive.
* @param squaredInputs If set, decreases the input sensitivity at low speeds.
*/
void DifferentialDrive::ArcadeDrive(double xSpeed, double zRotation,
bool squaredInputs) {
static bool reported = false;
@@ -100,21 +82,6 @@ void DifferentialDrive::ArcadeDrive(double xSpeed, double zRotation,
m_safetyHelper.Feed();
}
/**
* Curvature drive method for differential drive platform.
*
* The rotation argument controls the curvature of the robot's path rather than
* its rate of heading change. This makes the robot more controllable at high
* speeds. Also handles the robot's quick turn functionality - "quick turn"
* overrides constant-curvature turning for turn-in-place maneuvers.
*
* @param xSpeed The robot's speed along the X axis [-1.0..1.0]. Forward is
* positive.
* @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0].
* Clockwise is positive.
* @param isQuickTurn If set, overrides constant-curvature turning for
* turn-in-place maneuvers.
*/
void DifferentialDrive::CurvatureDrive(double xSpeed, double zRotation,
bool isQuickTurn) {
static bool reported = false;
@@ -188,15 +155,6 @@ void DifferentialDrive::CurvatureDrive(double xSpeed, double zRotation,
m_safetyHelper.Feed();
}
/**
* Tank drive method for differential drive platform.
*
* @param leftSpeed The robot left side's speed along the X axis
* [-1.0..1.0]. Forward is positive.
* @param rightSpeed The robot right side's speed along the X axis
* [-1.0..1.0]. Forward is positive.
* @param squaredInputs If set, decreases the input sensitivity at low speeds.
*/
void DifferentialDrive::TankDrive(double leftSpeed, double rightSpeed,
bool squaredInputs) {
static bool reported = false;
@@ -225,55 +183,18 @@ void DifferentialDrive::TankDrive(double leftSpeed, double rightSpeed,
m_safetyHelper.Feed();
}
/**
* Sets the QuickStop speed threshold in curvature drive.
*
* QuickStop compensates for the robot's moment of inertia when stopping after a
* QuickTurn.
*
* While QuickTurn is enabled, the QuickStop accumulator takes on the rotation
* rate value outputted by the low-pass filter when the robot's speed along the
* X axis is below the threshold. When QuickTurn is disabled, the accumulator's
* value is applied against the computed angular power request to slow the
* robot's rotation.
*
* @param threshold X speed below which quick stop accumulator will receive
* rotation rate values [0..1.0].
*/
void DifferentialDrive::SetQuickStopThreshold(double threshold) {
m_quickStopThreshold = threshold;
}
/**
* Sets the low-pass filter gain for QuickStop in curvature drive.
*
* The low-pass filter filters incoming rotation rate commands to smooth out
* high frequency changes.
*
* @param alpha Low-pass filter gain [0.0..2.0]. Smaller values result in slower
* output changes. Values between 1.0 and 2.0 result in output
* oscillation. Values below 0.0 and above 2.0 are unstable.
*/
void DifferentialDrive::SetQuickStopAlpha(double alpha) {
m_quickStopAlpha = alpha;
}
/**
* Gets if the power sent to the right side of the drivetrain is multipled by
* -1.
*
* @return true if the right side is inverted
*/
bool DifferentialDrive::IsRightSideInverted() const {
return m_rightSideInvertMultiplier == -1.0;
}
/**
* Sets if the power sent to the right side of the drivetrain should be
* multipled by -1.
*
* @param rightSideInverted true if right side power should be multipled by -1
*/
void DifferentialDrive::SetRightSideInverted(bool rightSideInverted) {
m_rightSideInvertMultiplier = rightSideInverted ? -1.0 : 1.0;
}

View File

@@ -19,39 +19,12 @@ using namespace frc;
constexpr double kPi = 3.14159265358979323846;
/**
* Construct a Killough drive with the given motors and default motor angles.
*
* The default motor angles make the wheels on each corner parallel to their
* respective opposite sides.
*
* If a motor needs to be inverted, do so before passing it in.
*
* @param leftMotor The motor on the left corner.
* @param rightMotor The motor on the right corner.
* @param backMotor The motor on the back corner.
*/
KilloughDrive::KilloughDrive(SpeedController& leftMotor,
SpeedController& rightMotor,
SpeedController& backMotor)
: KilloughDrive(leftMotor, rightMotor, backMotor, kDefaultLeftMotorAngle,
kDefaultRightMotorAngle, kDefaultBackMotorAngle) {}
/**
* Construct a Killough drive with the given motors.
*
* Angles are measured in degrees clockwise from the positive X axis.
*
* @param leftMotor The motor on the left corner.
* @param rightMotor The motor on the right corner.
* @param backMotor The motor on the back corner.
* @param leftMotorAngle The angle of the left wheel's forward direction of
* travel.
* @param rightMotorAngle The angle of the right wheel's forward direction of
* travel.
* @param backMotorAngle The angle of the back wheel's forward direction of
* travel.
*/
KilloughDrive::KilloughDrive(SpeedController& leftMotor,
SpeedController& rightMotor,
SpeedController& backMotor, double leftMotorAngle,
@@ -71,21 +44,6 @@ KilloughDrive::KilloughDrive(SpeedController& leftMotor,
SetName("KilloughDrive", instances);
}
/**
* Drive method for Killough platform.
*
* Angles are measured clockwise from the positive X axis. The robot's speed is
* independent from its angle or rotation rate.
*
* @param ySpeed The robot's speed along the Y axis [-1.0..1.0]. Right is
* positive.
* @param xSpeed The robot's speed along the X axis [-1.0..1.0]. Forward is
* positive.
* @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0].
* Clockwise is positive.
* @param gyroAngle The current angle reading from the gyro in degrees around
* the Z axis. Use this to implement field-oriented controls.
*/
void KilloughDrive::DriveCartesian(double ySpeed, double xSpeed,
double zRotation, double gyroAngle) {
if (!reported) {
@@ -118,19 +76,6 @@ void KilloughDrive::DriveCartesian(double ySpeed, double xSpeed,
m_safetyHelper.Feed();
}
/**
* Drive method for Killough platform.
*
* Angles are measured clockwise from the positive X axis. The robot's speed is
* independent from its angle or rotation rate.
*
* @param magnitude The robot's speed at a given angle [-1.0..1.0]. Forward is
* positive.
* @param angle The angle around the Z axis at which the robot drives in
* degrees [-180..180].
* @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0].
* Clockwise is positive.
*/
void KilloughDrive::DrivePolar(double magnitude, double angle,
double zRotation) {
if (!reported) {

View File

@@ -20,11 +20,6 @@ using namespace frc;
constexpr double kPi = 3.14159265358979323846;
/**
* Construct a MecanumDrive.
*
* If a motor needs to be inverted, do so before passing it in.
*/
MecanumDrive::MecanumDrive(SpeedController& frontLeftMotor,
SpeedController& rearLeftMotor,
SpeedController& frontRightMotor,
@@ -42,21 +37,6 @@ MecanumDrive::MecanumDrive(SpeedController& frontLeftMotor,
SetName("MecanumDrive", instances);
}
/**
* Drive method for Mecanum platform.
*
* Angles are measured clockwise from the positive X axis. The robot's speed is
* independent from its angle or rotation rate.
*
* @param ySpeed The robot's speed along the Y axis [-1.0..1.0]. Right is
* positive.
* @param xSpeed The robot's speed along the X axis [-1.0..1.0]. Forward is
* positive.
* @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0].
* Clockwise is positive.
* @param gyroAngle The current angle reading from the gyro in degrees around
* the Z axis. Use this to implement field-oriented controls.
*/
void MecanumDrive::DriveCartesian(double ySpeed, double xSpeed,
double zRotation, double gyroAngle) {
if (!reported) {
@@ -93,19 +73,6 @@ void MecanumDrive::DriveCartesian(double ySpeed, double xSpeed,
m_safetyHelper.Feed();
}
/**
* Drive method for Mecanum platform.
*
* Angles are measured clockwise from the positive X axis. The robot's speed is
* independent from its angle or rotation rate.
*
* @param magnitude The robot's speed at a given angle [-1.0..1.0]. Forward is
* positive.
* @param angle The angle around the Z axis at which the robot drives in
* degrees [-180..180].
* @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0].
* Clockwise is positive.
*/
void MecanumDrive::DrivePolar(double magnitude, double angle,
double zRotation) {
if (!reported) {
@@ -118,22 +85,10 @@ void MecanumDrive::DrivePolar(double magnitude, double angle,
magnitude * std::cos(angle * (kPi / 180.0)), zRotation, 0.0);
}
/**
* Gets if the power sent to the right side of the drivetrain is multipled by
* -1.
*
* @return true if the right side is inverted
*/
bool MecanumDrive::IsRightSideInverted() const {
return m_rightSideInvertMultiplier == -1.0;
}
/**
* Sets if the power sent to the right side of the drivetrain should be
* multipled by -1.
*
* @param rightSideInverted true if right side power should be multipled by -1
*/
void MecanumDrive::SetRightSideInverted(bool rightSideInverted) {
m_rightSideInvertMultiplier = rightSideInverted ? -1.0 : 1.0;
}

View File

@@ -20,32 +20,10 @@ using namespace frc;
RobotDriveBase::RobotDriveBase() { m_safetyHelper.SetSafetyEnabled(true); }
/**
* Sets the deadband applied to the drive inputs (e.g., joystick values).
*
* The default value is 0.02. Inputs smaller than the deadband are set to 0.0
* while inputs larger than the deadband are scaled from 0.0 to 1.0. See
* ApplyDeadband().
*
* @param deadband The deadband to set.
*/
void RobotDriveBase::SetDeadband(double deadband) { m_deadband = deadband; }
/**
* Configure the scaling factor for using RobotDrive with motor controllers in a
* mode other than PercentVbus or to limit the maximum output.
*
* @param maxOutput Multiplied with the output percentage computed by the drive
* functions.
*/
void RobotDriveBase::SetMaxOutput(double maxOutput) { m_maxOutput = maxOutput; }
/**
* Feed the motor safety object. Resets the timer that will stop the motors if
* it completes.
*
* @see MotorSafetyHelper::Feed()
*/
void RobotDriveBase::FeedWatchdog() { m_safetyHelper.Feed(); }
void RobotDriveBase::SetExpiration(double timeout) {
@@ -66,9 +44,6 @@ void RobotDriveBase::SetSafetyEnabled(bool enabled) {
m_safetyHelper.SetSafetyEnabled(enabled);
}
/**
* Limit motor values to the -1.0 to +1.0 range.
*/
double RobotDriveBase::Limit(double value) {
if (value > 1.0) {
return 1.0;
@@ -79,13 +54,6 @@ double RobotDriveBase::Limit(double value) {
return value;
}
/**
* Returns 0.0 if the given value is within the specified range around zero. The
* remaining range between the deadband and 1.0 is scaled from 0.0 to 1.0.
*
* @param value value to clip
* @param deadband range around zero
*/
double RobotDriveBase::ApplyDeadband(double value, double deadband) {
if (std::abs(value) > deadband) {
if (value > 0.0) {
@@ -98,9 +66,6 @@ double RobotDriveBase::ApplyDeadband(double value, double deadband) {
}
}
/**
* Normalize all wheel speeds if the magnitude of any wheel is greater than 1.0.
*/
void RobotDriveBase::Normalize(wpi::MutableArrayRef<double> wheelSpeeds) {
double maxMagnitude = std::abs(wheelSpeeds[0]);
for (size_t i = 1; i < wheelSpeeds.size(); i++) {

View File

@@ -18,11 +18,6 @@ Vector2d::Vector2d(double x, double y) {
this->y = y;
}
/**
* Rotate a vector in Cartesian space.
*
* @param angle angle in degrees by which to rotate vector counter-clockwise.
*/
void Vector2d::Rotate(double angle) {
double cosA = std::cos(angle * (kPi / 180.0));
double sinA = std::sin(angle * (kPi / 180.0));
@@ -33,25 +28,12 @@ void Vector2d::Rotate(double angle) {
y = out[1];
}
/**
* Returns dot product of this vector with argument.
*
* @param vec Vector with which to perform dot product.
*/
double Vector2d::Dot(const Vector2d& vec) const {
return x * vec.x + y * vec.y;
}
/**
* Returns magnitude of vector.
*/
double Vector2d::Magnitude() const { return std::sqrt(x * x + y * y); }
/**
* Returns scalar projection of this vector onto argument.
*
* @param vec Vector onto which to project this vector.
*/
double Vector2d::ScalarProject(const Vector2d& vec) const {
return Dot(vec) / vec.Magnitude();
}

View File

@@ -81,43 +81,23 @@ DriverStation::~DriverStation() {
m_dsThread.join();
}
/**
* Return a pointer to the singleton DriverStation.
*
* @return Pointer to the DS instance
*/
DriverStation& DriverStation::GetInstance() {
static DriverStation instance;
return instance;
}
/**
* Report an error to the DriverStation messages window.
*
* The error is also printed to the program console.
*/
void DriverStation::ReportError(const wpi::Twine& error) {
wpi::SmallString<128> temp;
HAL_SendError(1, 1, 0, error.toNullTerminatedStringRef(temp).data(), "", "",
1);
}
/**
* Report a warning to the DriverStation messages window.
*
* The warning is also printed to the program console.
*/
void DriverStation::ReportWarning(const wpi::Twine& error) {
wpi::SmallString<128> temp;
HAL_SendError(0, 1, 0, error.toNullTerminatedStringRef(temp).data(), "", "",
1);
}
/**
* Report an error to the DriverStation messages window.
*
* The error is also printed to the program console.
*/
void DriverStation::ReportError(bool isError, int32_t code,
const wpi::Twine& error,
const wpi::Twine& location,
@@ -131,13 +111,6 @@ void DriverStation::ReportError(bool isError, int32_t code,
stack.toNullTerminatedStringRef(stackTemp).data(), 1);
}
/**
* The state of one joystick button. Button indexes begin at 1.
*
* @param stick The joystick to read.
* @param button The button index, beginning at 1.
* @return The state of the joystick button.
*/
bool DriverStation::GetStickButton(int stick, int button) {
if (stick < 0 || stick >= kJoystickPorts) {
wpi_setWPIError(BadJoystickIndex);
@@ -161,14 +134,6 @@ bool DriverStation::GetStickButton(int stick, int button) {
return m_joystickButtons[stick].buttons & 1 << (button - 1);
}
/**
* Whether one joystick button was pressed since the last check. Button indexes
* begin at 1.
*
* @param stick The joystick to read.
* @param button The button index, beginning at 1.
* @return Whether the joystick button was pressed since the last check.
*/
bool DriverStation::GetStickButtonPressed(int stick, int button) {
if (stick < 0 || stick >= kJoystickPorts) {
wpi_setWPIError(BadJoystickIndex);
@@ -198,14 +163,6 @@ bool DriverStation::GetStickButtonPressed(int stick, int button) {
}
}
/**
* Whether one joystick button was released since the last check. Button indexes
* begin at 1.
*
* @param stick The joystick to read.
* @param button The button index, beginning at 1.
* @return Whether the joystick button was released since the last check.
*/
bool DriverStation::GetStickButtonReleased(int stick, int button) {
if (stick < 0 || stick >= kJoystickPorts) {
wpi_setWPIError(BadJoystickIndex);
@@ -235,15 +192,6 @@ bool DriverStation::GetStickButtonReleased(int stick, int button) {
}
}
/**
* Get the value of the axis on a joystick.
*
* This depends on the mapping of the joystick connected to the specified port.
*
* @param stick The joystick to read.
* @param axis The analog axis value to read from the joystick.
* @return The value of the axis on the joystick.
*/
double DriverStation::GetStickAxis(int stick, int axis) {
if (stick < 0 || stick >= kJoystickPorts) {
wpi_setWPIError(BadJoystickIndex);
@@ -266,11 +214,6 @@ double DriverStation::GetStickAxis(int stick, int axis) {
return m_joystickAxes[stick].axes[axis];
}
/**
* Get the state of a POV on the joystick.
*
* @return the angle of the POV in degrees, or -1 if the POV is not pressed.
*/
int DriverStation::GetStickPOV(int stick, int pov) {
if (stick < 0 || stick >= kJoystickPorts) {
wpi_setWPIError(BadJoystickIndex);
@@ -293,12 +236,6 @@ int DriverStation::GetStickPOV(int stick, int pov) {
return m_joystickPOVs[stick].povs[pov];
}
/**
* The state of the buttons on the joystick.
*
* @param stick The joystick to read.
* @return The state of the buttons on the joystick.
*/
int DriverStation::GetStickButtons(int stick) const {
if (stick < 0 || stick >= kJoystickPorts) {
wpi_setWPIError(BadJoystickIndex);
@@ -309,12 +246,6 @@ int DriverStation::GetStickButtons(int stick) const {
return m_joystickButtons[stick].buttons;
}
/**
* Returns the number of axes on a given joystick port.
*
* @param stick The joystick port number
* @return The number of axes on the indicated joystick
*/
int DriverStation::GetStickAxisCount(int stick) const {
if (stick < 0 || stick >= kJoystickPorts) {
wpi_setWPIError(BadJoystickIndex);
@@ -325,12 +256,6 @@ int DriverStation::GetStickAxisCount(int stick) const {
return m_joystickAxes[stick].count;
}
/**
* Returns the number of POVs on a given joystick port.
*
* @param stick The joystick port number
* @return The number of POVs on the indicated joystick
*/
int DriverStation::GetStickPOVCount(int stick) const {
if (stick < 0 || stick >= kJoystickPorts) {
wpi_setWPIError(BadJoystickIndex);
@@ -341,12 +266,6 @@ int DriverStation::GetStickPOVCount(int stick) const {
return m_joystickPOVs[stick].count;
}
/**
* Returns the number of buttons on a given joystick port.
*
* @param stick The joystick port number
* @return The number of buttons on the indicated joystick
*/
int DriverStation::GetStickButtonCount(int stick) const {
if (stick < 0 || stick >= kJoystickPorts) {
wpi_setWPIError(BadJoystickIndex);
@@ -357,12 +276,6 @@ int DriverStation::GetStickButtonCount(int stick) const {
return m_joystickButtons[stick].count;
}
/**
* Returns a boolean indicating if the controller is an xbox controller.
*
* @param stick The joystick port number
* @return A boolean that is true if the controller is an xbox controller.
*/
bool DriverStation::GetJoystickIsXbox(int stick) const {
if (stick < 0 || stick >= kJoystickPorts) {
wpi_setWPIError(BadJoystickIndex);
@@ -373,12 +286,6 @@ bool DriverStation::GetJoystickIsXbox(int stick) const {
return static_cast<bool>(m_joystickDescriptor[stick].isXbox);
}
/**
* Returns the type of joystick at a given port.
*
* @param stick The joystick port number
* @return The HID type of joystick at the given port
*/
int DriverStation::GetJoystickType(int stick) const {
if (stick < 0 || stick >= kJoystickPorts) {
wpi_setWPIError(BadJoystickIndex);
@@ -389,12 +296,6 @@ int DriverStation::GetJoystickType(int stick) const {
return static_cast<int>(m_joystickDescriptor[stick].type);
}
/**
* Returns the name of the joystick at the given port.
*
* @param stick The joystick port number
* @return The name of the joystick at the given port
*/
std::string DriverStation::GetJoystickName(int stick) const {
if (stick < 0 || stick >= kJoystickPorts) {
wpi_setWPIError(BadJoystickIndex);
@@ -404,12 +305,6 @@ std::string DriverStation::GetJoystickName(int stick) const {
return m_joystickDescriptor[stick].name;
}
/**
* Returns the types of Axes on a given joystick port.
*
* @param stick The joystick port number and the target axis
* @return What type of axis the axis is reporting to be
*/
int DriverStation::GetJoystickAxisType(int stick, int axis) const {
if (stick < 0 || stick >= kJoystickPorts) {
wpi_setWPIError(BadJoystickIndex);
@@ -420,104 +315,50 @@ int DriverStation::GetJoystickAxisType(int stick, int axis) const {
return m_joystickDescriptor[stick].axisTypes[axis];
}
/**
* Check if the DS has enabled the robot.
*
* @return True if the robot is enabled and the DS is connected
*/
bool DriverStation::IsEnabled() const {
HAL_ControlWord controlWord;
UpdateControlWord(false, controlWord);
return controlWord.enabled && controlWord.dsAttached;
}
/**
* Check if the robot is disabled.
*
* @return True if the robot is explicitly disabled or the DS is not connected
*/
bool DriverStation::IsDisabled() const {
HAL_ControlWord controlWord;
UpdateControlWord(false, controlWord);
return !(controlWord.enabled && controlWord.dsAttached);
}
/**
* Check if the DS is commanding autonomous mode.
*
* @return True if the robot is being commanded to be in autonomous mode
*/
bool DriverStation::IsAutonomous() const {
HAL_ControlWord controlWord;
UpdateControlWord(false, controlWord);
return controlWord.autonomous;
}
/**
* Check if the DS is commanding teleop mode.
*
* @return True if the robot is being commanded to be in teleop mode
*/
bool DriverStation::IsOperatorControl() const {
HAL_ControlWord controlWord;
UpdateControlWord(false, controlWord);
return !(controlWord.autonomous || controlWord.test);
}
/**
* Check if the DS is commanding test mode.
*
* @return True if the robot is being commanded to be in test mode
*/
bool DriverStation::IsTest() const {
HAL_ControlWord controlWord;
UpdateControlWord(false, controlWord);
return controlWord.test;
}
/**
* Check if the DS is attached.
*
* @return True if the DS is connected to the robot
*/
bool DriverStation::IsDSAttached() const {
HAL_ControlWord controlWord;
UpdateControlWord(false, controlWord);
return controlWord.dsAttached;
}
/**
* Has a new control packet from the driver station arrived since the last time
* this function was called?
*
* Warning: If you call this function from more than one place at the same time,
* you will not get the intended behavior.
*
* @return True if the control data has been updated since the last call.
*/
bool DriverStation::IsNewControlData() const { return HAL_IsNewControlData(); }
/**
* Is the driver station attached to a Field Management System?
*
* @return True if the robot is competing on a field being controlled by a Field
* Management System
*/
bool DriverStation::IsFMSAttached() const {
HAL_ControlWord controlWord;
UpdateControlWord(false, controlWord);
return controlWord.fmsAttached;
}
/**
* Check if the FPGA outputs are enabled.
*
* The outputs may be disabled if the robot is disabled or e-stopped, the
* watchdog has expired, or if the roboRIO browns out.
*
* @return True if the FPGA outputs are enabled.
* @deprecated Use RobotController static class method
*/
bool DriverStation::IsSysActive() const {
int32_t status = 0;
bool retVal = HAL_GetSystemActive(&status);
@@ -525,12 +366,6 @@ bool DriverStation::IsSysActive() const {
return retVal;
}
/**
* Check if the system is browned out.
*
* @return True if the system is browned out
* @deprecated Use RobotController static class method
*/
bool DriverStation::IsBrownedOut() const {
int32_t status = 0;
bool retVal = HAL_GetBrownedOut(&status);
@@ -563,13 +398,6 @@ int DriverStation::GetReplayNumber() const {
return m_matchInfo->replayNumber;
}
/**
* Return the alliance that the driver station says it is on.
*
* This could return kRed or kBlue.
*
* @return The Alliance enum (kRed, kBlue or kInvalid)
*/
DriverStation::Alliance DriverStation::GetAlliance() const {
int32_t status = 0;
auto allianceStationID = HAL_GetAllianceStation(&status);
@@ -587,13 +415,6 @@ DriverStation::Alliance DriverStation::GetAlliance() const {
}
}
/**
* Return the driver station location on the field.
*
* This could return 1, 2, or 3.
*
* @return The location of the driver station (1-3, 0 for invalid)
*/
int DriverStation::GetLocation() const {
int32_t status = 0;
auto allianceStationID = HAL_GetAllianceStation(&status);
@@ -612,32 +433,8 @@ int DriverStation::GetLocation() const {
}
}
/**
* Wait until a new packet comes from the driver station.
*
* This blocks on a semaphore, so the waiting is efficient.
*
* This is a good way to delay processing until there is new driver station data
* to act on.
*/
void DriverStation::WaitForData() { WaitForData(0); }
/**
* Wait until a new packet comes from the driver station, or wait for a timeout.
*
* If the timeout is less then or equal to 0, wait indefinitely.
*
* Timeout is in milliseconds
*
* This blocks on a semaphore, so the waiting is efficient.
*
* This is a good way to delay processing until there is new driver station data
* to act on.
*
* @param timeout Timeout time in seconds
*
* @return true if new data, otherwise false
*/
bool DriverStation::WaitForData(double timeout) {
auto timeoutTime =
std::chrono::steady_clock::now() + std::chrono::duration<double>(timeout);
@@ -657,31 +454,11 @@ bool DriverStation::WaitForData(double timeout) {
return true;
}
/**
* Return the approximate match time.
*
* The FMS does not send an official match time to the robots, but does send an
* approximate match time. The value will count down the time remaining in the
* current period (auto or teleop).
*
* Warning: This is not an official time (so it cannot be used to dispute ref
* calls or guarantee that a function will trigger before the match ends).
*
* The Practice Match function of the DS approximates the behaviour seen on the
* field.
*
* @return Time remaining in current match period (auto or teleop)
*/
double DriverStation::GetMatchTime() const {
int32_t status;
return HAL_GetMatchTime(&status);
}
/**
* Read the battery voltage.
*
* @return The battery voltage in Volts.
*/
double DriverStation::GetBatteryVoltage() const {
int32_t status = 0;
double voltage = HAL_GetVinVoltage(&status);
@@ -690,6 +467,155 @@ double DriverStation::GetBatteryVoltage() const {
return voltage;
}
void DriverStation::GetData() {
// Get the status of all of the joysticks, and save to the cache
for (uint8_t stick = 0; stick < kJoystickPorts; stick++) {
HAL_GetJoystickAxes(stick, &m_joystickAxesCache[stick]);
HAL_GetJoystickPOVs(stick, &m_joystickPOVsCache[stick]);
HAL_GetJoystickButtons(stick, &m_joystickButtonsCache[stick]);
HAL_GetJoystickDescriptor(stick, &m_joystickDescriptorCache[stick]);
}
// Grab match specific data
HAL_MatchInfo matchInfo;
auto status = HAL_GetMatchInfo(&matchInfo);
if (status == 0) {
m_matchInfoCache->eventName = matchInfo.eventName;
m_matchInfoCache->matchNumber = matchInfo.matchNumber;
m_matchInfoCache->replayNumber = matchInfo.replayNumber;
m_matchInfoCache->matchType =
static_cast<DriverStation::MatchType>(matchInfo.matchType);
m_matchInfoCache->gameSpecificMessage = matchInfo.gameSpecificMessage;
}
HAL_FreeMatchInfo(&matchInfo);
// Force a control word update, to make sure the data is the newest.
HAL_ControlWord controlWord;
UpdateControlWord(true, controlWord);
{
// Obtain a write lock on the data, swap the cached data into the
// main data arrays
std::lock_guard<wpi::mutex> lock(m_cacheDataMutex);
for (int32_t i = 0; i < kJoystickPorts; i++) {
// If buttons weren't pressed and are now, set flags in m_buttonsPressed
m_joystickButtonsPressed[i] |=
~m_joystickButtons[i].buttons & m_joystickButtonsCache[i].buttons;
// If buttons were pressed and aren't now, set flags in m_buttonsReleased
m_joystickButtonsReleased[i] |=
m_joystickButtons[i].buttons & ~m_joystickButtonsCache[i].buttons;
}
m_joystickAxes.swap(m_joystickAxesCache);
m_joystickPOVs.swap(m_joystickPOVsCache);
m_joystickButtons.swap(m_joystickButtonsCache);
m_joystickDescriptor.swap(m_joystickDescriptorCache);
m_matchInfo.swap(m_matchInfoCache);
}
{
std::lock_guard<wpi::mutex> waitLock(m_waitForDataMutex);
// Nofify all threads
m_waitForDataCounter++;
m_waitForDataCond.notify_all();
}
SendMatchData();
}
DriverStation::DriverStation() {
HAL_Initialize(500, 0);
m_waitForDataCounter = 0;
m_joystickAxes = std::make_unique<HAL_JoystickAxes[]>(kJoystickPorts);
m_joystickPOVs = std::make_unique<HAL_JoystickPOVs[]>(kJoystickPorts);
m_joystickButtons = std::make_unique<HAL_JoystickButtons[]>(kJoystickPorts);
m_joystickDescriptor =
std::make_unique<HAL_JoystickDescriptor[]>(kJoystickPorts);
m_matchInfo = std::make_unique<MatchInfoData>();
m_joystickAxesCache = std::make_unique<HAL_JoystickAxes[]>(kJoystickPorts);
m_joystickPOVsCache = std::make_unique<HAL_JoystickPOVs[]>(kJoystickPorts);
m_joystickButtonsCache =
std::make_unique<HAL_JoystickButtons[]>(kJoystickPorts);
m_joystickDescriptorCache =
std::make_unique<HAL_JoystickDescriptor[]>(kJoystickPorts);
m_matchInfoCache = std::make_unique<MatchInfoData>();
m_matchDataSender = std::make_unique<MatchDataSender>();
// All joysticks should default to having zero axes, povs and buttons, so
// uninitialized memory doesn't get sent to speed controllers.
for (unsigned int i = 0; i < kJoystickPorts; i++) {
m_joystickAxes[i].count = 0;
m_joystickPOVs[i].count = 0;
m_joystickButtons[i].count = 0;
m_joystickDescriptor[i].isXbox = 0;
m_joystickDescriptor[i].type = -1;
m_joystickDescriptor[i].name[0] = '\0';
m_joystickAxesCache[i].count = 0;
m_joystickPOVsCache[i].count = 0;
m_joystickButtonsCache[i].count = 0;
m_joystickDescriptorCache[i].isXbox = 0;
m_joystickDescriptorCache[i].type = -1;
m_joystickDescriptorCache[i].name[0] = '\0';
m_joystickButtonsPressed[i] = 0;
m_joystickButtonsReleased[i] = 0;
}
m_dsThread = std::thread(&DriverStation::Run, this);
}
void DriverStation::ReportJoystickUnpluggedError(const wpi::Twine& message) {
double currentTime = Timer::GetFPGATimestamp();
if (currentTime > m_nextMessageTime) {
ReportError(message);
m_nextMessageTime = currentTime + kJoystickUnpluggedMessageInterval;
}
}
void DriverStation::ReportJoystickUnpluggedWarning(const wpi::Twine& message) {
double currentTime = Timer::GetFPGATimestamp();
if (currentTime > m_nextMessageTime) {
ReportWarning(message);
m_nextMessageTime = currentTime + kJoystickUnpluggedMessageInterval;
}
}
void DriverStation::Run() {
m_isRunning = true;
int safetyCounter = 0;
while (m_isRunning) {
HAL_WaitForDSData();
GetData();
if (IsDisabled()) safetyCounter = 0;
if (++safetyCounter >= 4) {
MotorSafetyHelper::CheckMotors();
safetyCounter = 0;
}
if (m_userInDisabled) HAL_ObserveUserProgramDisabled();
if (m_userInAutonomous) HAL_ObserveUserProgramAutonomous();
if (m_userInTeleop) HAL_ObserveUserProgramTeleop();
if (m_userInTest) HAL_ObserveUserProgramTest();
}
}
void DriverStation::UpdateControlWord(bool force,
HAL_ControlWord& controlWord) const {
auto now = std::chrono::steady_clock::now();
std::lock_guard<wpi::mutex> lock(m_controlWordMutex);
// Update every 50 ms or on force.
if ((now - m_lastControlWordUpdate > std::chrono::milliseconds(50)) ||
force) {
HAL_GetControlWord(&m_controlWordCache);
m_lastControlWordUpdate = now;
}
controlWord = m_controlWordCache;
}
void DriverStation::SendMatchData() {
int32_t status = 0;
HAL_AllianceStationID alliance = HAL_GetAllianceStation(&status);
@@ -748,181 +674,3 @@ void DriverStation::SendMatchData() {
std::memcpy(&wordInt, &ctlWord, sizeof(wordInt));
m_matchDataSender->controlWord.SetDouble(wordInt);
}
/**
* Copy data from the DS task for the user.
*
* If no new data exists, it will just be returned, otherwise
* the data will be copied from the DS polling loop.
*/
void DriverStation::GetData() {
// Get the status of all of the joysticks, and save to the cache
for (uint8_t stick = 0; stick < kJoystickPorts; stick++) {
HAL_GetJoystickAxes(stick, &m_joystickAxesCache[stick]);
HAL_GetJoystickPOVs(stick, &m_joystickPOVsCache[stick]);
HAL_GetJoystickButtons(stick, &m_joystickButtonsCache[stick]);
HAL_GetJoystickDescriptor(stick, &m_joystickDescriptorCache[stick]);
}
// Grab match specific data
HAL_MatchInfo matchInfo;
auto status = HAL_GetMatchInfo(&matchInfo);
if (status == 0) {
m_matchInfoCache->eventName = matchInfo.eventName;
m_matchInfoCache->matchNumber = matchInfo.matchNumber;
m_matchInfoCache->replayNumber = matchInfo.replayNumber;
m_matchInfoCache->matchType =
static_cast<DriverStation::MatchType>(matchInfo.matchType);
m_matchInfoCache->gameSpecificMessage = matchInfo.gameSpecificMessage;
}
HAL_FreeMatchInfo(&matchInfo);
// Force a control word update, to make sure the data is the newest.
HAL_ControlWord controlWord;
UpdateControlWord(true, controlWord);
{
// Obtain a write lock on the data, swap the cached data into the
// main data arrays
std::lock_guard<wpi::mutex> lock(m_cacheDataMutex);
for (int32_t i = 0; i < kJoystickPorts; i++) {
// If buttons weren't pressed and are now, set flags in m_buttonsPressed
m_joystickButtonsPressed[i] |=
~m_joystickButtons[i].buttons & m_joystickButtonsCache[i].buttons;
// If buttons were pressed and aren't now, set flags in m_buttonsReleased
m_joystickButtonsReleased[i] |=
m_joystickButtons[i].buttons & ~m_joystickButtonsCache[i].buttons;
}
m_joystickAxes.swap(m_joystickAxesCache);
m_joystickPOVs.swap(m_joystickPOVsCache);
m_joystickButtons.swap(m_joystickButtonsCache);
m_joystickDescriptor.swap(m_joystickDescriptorCache);
m_matchInfo.swap(m_matchInfoCache);
}
{
std::lock_guard<wpi::mutex> waitLock(m_waitForDataMutex);
// Nofify all threads
m_waitForDataCounter++;
m_waitForDataCond.notify_all();
}
SendMatchData();
}
/**
* DriverStation constructor.
*
* This is only called once the first time GetInstance() is called
*/
DriverStation::DriverStation() {
HAL_Initialize(500, 0);
m_waitForDataCounter = 0;
m_joystickAxes = std::make_unique<HAL_JoystickAxes[]>(kJoystickPorts);
m_joystickPOVs = std::make_unique<HAL_JoystickPOVs[]>(kJoystickPorts);
m_joystickButtons = std::make_unique<HAL_JoystickButtons[]>(kJoystickPorts);
m_joystickDescriptor =
std::make_unique<HAL_JoystickDescriptor[]>(kJoystickPorts);
m_matchInfo = std::make_unique<MatchInfoData>();
m_joystickAxesCache = std::make_unique<HAL_JoystickAxes[]>(kJoystickPorts);
m_joystickPOVsCache = std::make_unique<HAL_JoystickPOVs[]>(kJoystickPorts);
m_joystickButtonsCache =
std::make_unique<HAL_JoystickButtons[]>(kJoystickPorts);
m_joystickDescriptorCache =
std::make_unique<HAL_JoystickDescriptor[]>(kJoystickPorts);
m_matchInfoCache = std::make_unique<MatchInfoData>();
m_matchDataSender = std::make_unique<MatchDataSender>();
// All joysticks should default to having zero axes, povs and buttons, so
// uninitialized memory doesn't get sent to speed controllers.
for (unsigned int i = 0; i < kJoystickPorts; i++) {
m_joystickAxes[i].count = 0;
m_joystickPOVs[i].count = 0;
m_joystickButtons[i].count = 0;
m_joystickDescriptor[i].isXbox = 0;
m_joystickDescriptor[i].type = -1;
m_joystickDescriptor[i].name[0] = '\0';
m_joystickAxesCache[i].count = 0;
m_joystickPOVsCache[i].count = 0;
m_joystickButtonsCache[i].count = 0;
m_joystickDescriptorCache[i].isXbox = 0;
m_joystickDescriptorCache[i].type = -1;
m_joystickDescriptorCache[i].name[0] = '\0';
m_joystickButtonsPressed[i] = 0;
m_joystickButtonsReleased[i] = 0;
}
m_dsThread = std::thread(&DriverStation::Run, this);
}
/**
* Reports errors related to unplugged joysticks
* Throttles the errors so that they don't overwhelm the DS
*/
void DriverStation::ReportJoystickUnpluggedError(const wpi::Twine& message) {
double currentTime = Timer::GetFPGATimestamp();
if (currentTime > m_nextMessageTime) {
ReportError(message);
m_nextMessageTime = currentTime + kJoystickUnpluggedMessageInterval;
}
}
/**
* Reports errors related to unplugged joysticks.
*
* Throttles the errors so that they don't overwhelm the DS.
*/
void DriverStation::ReportJoystickUnpluggedWarning(const wpi::Twine& message) {
double currentTime = Timer::GetFPGATimestamp();
if (currentTime > m_nextMessageTime) {
ReportWarning(message);
m_nextMessageTime = currentTime + kJoystickUnpluggedMessageInterval;
}
}
void DriverStation::Run() {
m_isRunning = true;
int safetyCounter = 0;
while (m_isRunning) {
HAL_WaitForDSData();
GetData();
if (IsDisabled()) safetyCounter = 0;
if (++safetyCounter >= 4) {
MotorSafetyHelper::CheckMotors();
safetyCounter = 0;
}
if (m_userInDisabled) HAL_ObserveUserProgramDisabled();
if (m_userInAutonomous) HAL_ObserveUserProgramAutonomous();
if (m_userInTeleop) HAL_ObserveUserProgramTeleop();
if (m_userInTest) HAL_ObserveUserProgramTest();
}
}
/**
* Gets ControlWord data from the cache. If 50ms has passed, or the force
* parameter is set, the cached data is updated. Otherwise the data is just
* copied from the cache.
*
* @param force True to force an update to the cache, otherwise update if 50ms
* have passed.
* @param controlWord Structure to put the return control word data into.
*/
void DriverStation::UpdateControlWord(bool force,
HAL_ControlWord& controlWord) const {
auto now = std::chrono::steady_clock::now();
std::lock_guard<wpi::mutex> lock(m_controlWordMutex);
// Update every 50 ms or on force.
if ((now - m_lastControlWordUpdate > std::chrono::milliseconds(50)) ||
force) {
HAL_GetControlWord(&m_controlWordCache);
m_lastControlWordUpdate = now;
}
controlWord = m_controlWordCache;
}

View File

@@ -15,62 +15,6 @@
using namespace frc;
/**
* Common initialization code for Encoders.
*
* This code allocates resources for Encoders and is common to all constructors.
*
* The counter will start counting immediately.
*
* @param reverseDirection If true, counts down instead of up (this is all
* relative)
* @param encodingType either k1X, k2X, or k4X to indicate 1X, 2X or 4X
* decoding. If 4X is selected, then an encoder FPGA
* object is used and the returned counts will be 4x
* the encoder spec'd value since all rising and
* falling edges are counted. If 1X or 2X are selected
* then a counter object will be used and the returned
* value will either exactly match the spec'd count or
* be double (2x) the spec'd count.
*/
void Encoder::InitEncoder(bool reverseDirection, EncodingType encodingType) {
int32_t status = 0;
m_encoder = HAL_InitializeEncoder(
m_aSource->GetPortHandleForRouting(),
(HAL_AnalogTriggerType)m_aSource->GetAnalogTriggerTypeForRouting(),
m_bSource->GetPortHandleForRouting(),
(HAL_AnalogTriggerType)m_bSource->GetAnalogTriggerTypeForRouting(),
reverseDirection, (HAL_EncoderEncodingType)encodingType, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
HAL_Report(HALUsageReporting::kResourceType_Encoder, GetFPGAIndex(),
encodingType);
SetName("Encoder", m_aSource->GetChannel());
}
/**
* Encoder constructor.
*
* Construct a Encoder given a and b channels.
*
* The counter will start counting immediately.
*
* @param aChannel The a channel DIO channel. 0-9 are on-board, 10-25
* are on the MXP port
* @param bChannel The b channel DIO channel. 0-9 are on-board, 10-25
* are on the MXP port
* @param reverseDirection represents the orientation of the encoder and
* inverts the output values if necessary so forward
* represents positive values.
* @param encodingType either k1X, k2X, or k4X to indicate 1X, 2X or 4X
* decoding. If 4X is selected, then an encoder FPGA
* object is used and the returned counts will be 4x
* the encoder spec'd value since all rising and
* falling edges are counted. If 1X or 2X are selected
* then a counter object will be used and the returned
* value will either exactly match the spec'd count or
* be double (2x) the spec'd count.
*/
Encoder::Encoder(int aChannel, int bChannel, bool reverseDirection,
EncodingType encodingType) {
m_aSource = std::make_shared<DigitalInput>(aChannel);
@@ -80,29 +24,6 @@ Encoder::Encoder(int aChannel, int bChannel, bool reverseDirection,
AddChild(m_bSource);
}
/**
* Encoder constructor.
*
* Construct a Encoder given a and b channels as digital inputs. This is used in
* the case where the digital inputs are shared. The Encoder class will not
* allocate the digital inputs and assume that they already are counted.
*
* The counter will start counting immediately.
*
* @param aSource The source that should be used for the a channel.
* @param bSource the source that should be used for the b channel.
* @param reverseDirection represents the orientation of the encoder and
* inverts the output values if necessary so forward
* represents positive values.
* @param encodingType either k1X, k2X, or k4X to indicate 1X, 2X or 4X
* decoding. If 4X is selected, then an encoder FPGA
* object is used and the returned counts will be 4x
* the encoder spec'd value since all rising and
* falling edges are counted. If 1X or 2X are selected
* then a counter object will be used and the returned
* value will either exactly match the spec'd count or
* be double (2x) the spec'd count.
*/
Encoder::Encoder(DigitalSource* aSource, DigitalSource* bSource,
bool reverseDirection, EncodingType encodingType)
: m_aSource(aSource, NullDeleter<DigitalSource>()),
@@ -113,6 +34,13 @@ Encoder::Encoder(DigitalSource* aSource, DigitalSource* bSource,
InitEncoder(reverseDirection, encodingType);
}
Encoder::Encoder(DigitalSource& aSource, DigitalSource& bSource,
bool reverseDirection, EncodingType encodingType)
: m_aSource(&aSource, NullDeleter<DigitalSource>()),
m_bSource(&bSource, NullDeleter<DigitalSource>()) {
InitEncoder(reverseDirection, encodingType);
}
Encoder::Encoder(std::shared_ptr<DigitalSource> aSource,
std::shared_ptr<DigitalSource> bSource, bool reverseDirection,
EncodingType encodingType)
@@ -123,84 +51,12 @@ Encoder::Encoder(std::shared_ptr<DigitalSource> aSource,
InitEncoder(reverseDirection, encodingType);
}
/**
* Encoder constructor.
*
* Construct a Encoder given a and b channels as digital inputs. This is used in
* the case where the digital inputs are shared. The Encoder class will not
* allocate the digital inputs and assume that they already are counted.
*
* The counter will start counting immediately.
*
* @param aSource The source that should be used for the a channel.
* @param bSource the source that should be used for the b channel.
* @param reverseDirection represents the orientation of the encoder and
* inverts the output values if necessary so forward
* represents positive values.
* @param encodingType either k1X, k2X, or k4X to indicate 1X, 2X or 4X
* decoding. If 4X is selected, then an encoder FPGA
* object is used and the returned counts will be 4x
* the encoder spec'd value since all rising and
* falling edges are counted. If 1X or 2X are selected
* then a counter object will be used and the returned
* value will either exactly match the spec'd count or
* be double (2x) the spec'd count.
*/
Encoder::Encoder(DigitalSource& aSource, DigitalSource& bSource,
bool reverseDirection, EncodingType encodingType)
: m_aSource(&aSource, NullDeleter<DigitalSource>()),
m_bSource(&bSource, NullDeleter<DigitalSource>()) {
InitEncoder(reverseDirection, encodingType);
}
/**
* Free the resources for an Encoder.
*
* Frees the FPGA resources associated with an Encoder.
*/
Encoder::~Encoder() {
int32_t status = 0;
HAL_FreeEncoder(m_encoder, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* The encoding scale factor 1x, 2x, or 4x, per the requested encodingType.
*
* Used to divide raw edge counts down to spec'd counts.
*/
int Encoder::GetEncodingScale() const {
int32_t status = 0;
int val = HAL_GetEncoderEncodingScale(m_encoder, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
return val;
}
/**
* Gets the raw value from the encoder.
*
* The raw value is the actual count unscaled by the 1x, 2x, or 4x scale
* factor.
*
* @return Current raw count from the encoder
*/
int Encoder::GetRaw() const {
if (StatusIsFatal()) return 0;
int32_t status = 0;
int value = HAL_GetEncoderRaw(m_encoder, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
return value;
}
/**
* Gets the current count.
*
* Returns the current count on the Encoder. This method compensates for the
* decoding type.
*
* @return Current count from the Encoder adjusted for the 1x, 2x, or 4x scale
* factor.
*/
int Encoder::Get() const {
if (StatusIsFatal()) return 0;
int32_t status = 0;
@@ -209,11 +65,6 @@ int Encoder::Get() const {
return value;
}
/**
* Reset the Encoder distance to zero.
*
* Resets the current count to zero on the encoder.
*/
void Encoder::Reset() {
if (StatusIsFatal()) return;
int32_t status = 0;
@@ -221,17 +72,6 @@ void Encoder::Reset() {
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Returns the period of the most recent pulse.
*
* Returns the period of the most recent Encoder pulse in seconds. This method
* compensates for the decoding type.
*
* Warning: This returns unscaled periods. Use GetRate() for rates that are
* scaled using the value from SetDistancePerPulse().
*
* @return Period in seconds of the most recent pulse.
*/
double Encoder::GetPeriod() const {
if (StatusIsFatal()) return 0.0;
int32_t status = 0;
@@ -240,22 +80,6 @@ double Encoder::GetPeriod() const {
return value;
}
/**
* Sets the maximum period for stopped detection.
*
* Sets the value that represents the maximum period of the Encoder before it
* will assume that the attached device is stopped. This timeout allows users
* to determine if the wheels or other shaft has stopped rotating.
* This method compensates for the decoding type.
*
* @deprecated Use SetMinRate() in favor of this method. This takes unscaled
* periods and SetMinRate() scales using value from
* SetDistancePerPulse().
*
* @param maxPeriod The maximum time between rising and falling edges before
* the FPGA will report the device stopped. This is expressed
* in seconds.
*/
void Encoder::SetMaxPeriod(double maxPeriod) {
if (StatusIsFatal()) return;
int32_t status = 0;
@@ -263,15 +87,6 @@ void Encoder::SetMaxPeriod(double maxPeriod) {
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Determine if the encoder is stopped.
*
* Using the MaxPeriod value, a boolean is returned that is true if the encoder
* is considered stopped and false if it is still moving. A stopped encoder is
* one where the most recent pulse width exceeds the MaxPeriod.
*
* @return True if the encoder is considered stopped.
*/
bool Encoder::GetStopped() const {
if (StatusIsFatal()) return true;
int32_t status = 0;
@@ -280,11 +95,6 @@ bool Encoder::GetStopped() const {
return value;
}
/**
* The last direction the encoder value changed.
*
* @return The last direction the encoder value changed.
*/
bool Encoder::GetDirection() const {
if (StatusIsFatal()) return false;
int32_t status = 0;
@@ -293,24 +103,21 @@ bool Encoder::GetDirection() const {
return value;
}
/**
* The scale needed to convert a raw counter value into a number of encoder
* pulses.
*/
double Encoder::DecodingScaleFactor() const {
if (StatusIsFatal()) return 0.0;
int Encoder::GetRaw() const {
if (StatusIsFatal()) return 0;
int32_t status = 0;
double val = HAL_GetEncoderDecodingScaleFactor(m_encoder, &status);
int value = HAL_GetEncoderRaw(m_encoder, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
return value;
}
int Encoder::GetEncodingScale() const {
int32_t status = 0;
int val = HAL_GetEncoderEncodingScale(m_encoder, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
return val;
}
/**
* Get the distance the robot has driven since the last reset.
*
* @return The distance driven since the last reset as scaled by the value from
* SetDistancePerPulse().
*/
double Encoder::GetDistance() const {
if (StatusIsFatal()) return 0.0;
int32_t status = 0;
@@ -319,14 +126,6 @@ double Encoder::GetDistance() const {
return value;
}
/**
* Get the current rate of the encoder.
*
* Units are distance per second as scaled by the value from
* SetDistancePerPulse().
*
* @return The current rate of the encoder.
*/
double Encoder::GetRate() const {
if (StatusIsFatal()) return 0.0;
int32_t status = 0;
@@ -335,12 +134,6 @@ double Encoder::GetRate() const {
return value;
}
/**
* Set the minimum rate of the device before the hardware reports it stopped.
*
* @param minRate The minimum rate. The units are in distance per second as
* scaled by the value from SetDistancePerPulse().
*/
void Encoder::SetMinRate(double minRate) {
if (StatusIsFatal()) return;
int32_t status = 0;
@@ -348,23 +141,6 @@ void Encoder::SetMinRate(double minRate) {
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Set the distance per pulse for this encoder.
*
* This sets the multiplier used to determine the distance driven based on the
* count value from the encoder.
*
* Do not include the decoding type in this scale. The library already
* compensates for the decoding type.
*
* Set this value based on the encoder's rated Pulses per Revolution and
* factor in gearing reductions following the encoder shaft.
*
* This distance can be in any units you like, linear or angular.
*
* @param distancePerPulse The scale factor that will be used to convert pulses
* to useful units.
*/
void Encoder::SetDistancePerPulse(double distancePerPulse) {
if (StatusIsFatal()) return;
int32_t status = 0;
@@ -372,11 +148,6 @@ void Encoder::SetDistancePerPulse(double distancePerPulse) {
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Get the distance per pulse for this encoder.
*
* @return The scale factor that will be used to convert pulses to useful units.
*/
double Encoder::GetDistancePerPulse() const {
if (StatusIsFatal()) return 0.0;
int32_t status = 0;
@@ -385,14 +156,6 @@ double Encoder::GetDistancePerPulse() const {
return distancePerPulse;
}
/**
* Set the direction sensing for this encoder.
*
* This sets the direction sensing on the encoder so that it could count in the
* correct software direction regardless of the mounting.
*
* @param reverseDirection true if the encoder direction should be reversed
*/
void Encoder::SetReverseDirection(bool reverseDirection) {
if (StatusIsFatal()) return;
int32_t status = 0;
@@ -400,15 +163,6 @@ void Encoder::SetReverseDirection(bool reverseDirection) {
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Set the Samples to Average which specifies the number of samples of the timer
* to average when calculating the period.
*
* Perform averaging to account for mechanical imperfections or as oversampling
* to increase resolution.
*
* @param samplesToAverage The number of samples to average from 1 to 127.
*/
void Encoder::SetSamplesToAverage(int samplesToAverage) {
if (samplesToAverage < 1 || samplesToAverage > 127) {
wpi_setWPIErrorWithContext(
@@ -421,15 +175,6 @@ void Encoder::SetSamplesToAverage(int samplesToAverage) {
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Get the Samples to Average which specifies the number of samples of the timer
* to average when calculating the period.
*
* Perform averaging to account for mechanical imperfections or as oversampling
* to increase resolution.
*
* @return The number of samples being averaged (from 1 to 127)
*/
int Encoder::GetSamplesToAverage() const {
int32_t status = 0;
int result = HAL_GetEncoderSamplesToAverage(m_encoder, &status);
@@ -437,11 +182,6 @@ int Encoder::GetSamplesToAverage() const {
return result;
}
/**
* Implement the PIDSource interface.
*
* @return The current value of the selected source parameter.
*/
double Encoder::PIDGet() {
if (StatusIsFatal()) return 0.0;
switch (GetPIDSourceType()) {
@@ -454,14 +194,6 @@ double Encoder::PIDGet() {
}
}
/**
* Set the index source for the encoder.
*
* When this source is activated, the encoder count automatically resets.
*
* @param channel A DIO channel to set as the encoder index
* @param type The state that will cause the encoder to reset
*/
void Encoder::SetIndexSource(int channel, Encoder::IndexingType type) {
// Force digital input if just given an index
m_indexSource = std::make_shared<DigitalInput>(channel);
@@ -469,14 +201,6 @@ void Encoder::SetIndexSource(int channel, Encoder::IndexingType type) {
SetIndexSource(*m_indexSource.get(), type);
}
/**
* Set the index source for the encoder.
*
* When this source is activated, the encoder count automatically resets.
*
* @param channel A digital source to set as the encoder index
* @param type The state that will cause the encoder to reset
*/
void Encoder::SetIndexSource(const DigitalSource& source,
Encoder::IndexingType type) {
int32_t status = 0;
@@ -509,3 +233,26 @@ void Encoder::InitSendable(SendableBuilder& builder) {
builder.AddDoubleProperty("Distance per Tick",
[=]() { return GetDistancePerPulse(); }, nullptr);
}
void Encoder::InitEncoder(bool reverseDirection, EncodingType encodingType) {
int32_t status = 0;
m_encoder = HAL_InitializeEncoder(
m_aSource->GetPortHandleForRouting(),
(HAL_AnalogTriggerType)m_aSource->GetAnalogTriggerTypeForRouting(),
m_bSource->GetPortHandleForRouting(),
(HAL_AnalogTriggerType)m_bSource->GetAnalogTriggerTypeForRouting(),
reverseDirection, (HAL_EncoderEncodingType)encodingType, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
HAL_Report(HALUsageReporting::kResourceType_Encoder, GetFPGAIndex(),
encodingType);
SetName("Encoder", m_aSource->GetChannel());
}
double Encoder::DecodingScaleFactor() const {
if (StatusIsFatal()) return 0.0;
int32_t status = 0;
double val = HAL_GetEncoderDecodingScaleFactor(m_encoder, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
return val;
}

View File

@@ -26,29 +26,12 @@ Error ErrorBase::_globalError;
ErrorBase::ErrorBase() { HAL_Initialize(500, 0); }
/**
* @brief Retrieve the current error.
*
* Get the current error information associated with this sensor.
*/
Error& ErrorBase::GetError() { return m_error; }
const Error& ErrorBase::GetError() const { return m_error; }
/**
* @brief Clear the current error information associated with this sensor.
*/
void ErrorBase::ClearError() const { m_error.Clear(); }
/**
* @brief Set error information associated with a C library call that set an
* error to the "errno" global variable.
*
* @param contextMessage A custom message from the code that set the error.
* @param filename Filename of the error source
* @param function Function of the error source
* @param lineNumber Line number of the error source
*/
void ErrorBase::SetErrnoError(const wpi::Twine& contextMessage,
wpi::StringRef filename, wpi::StringRef function,
int lineNumber) const {
@@ -73,16 +56,6 @@ void ErrorBase::SetErrnoError(const wpi::Twine& contextMessage,
}
}
/**
* @brief Set the current error information associated from the nivision Imaq
* API.
*
* @param success The return from the function
* @param contextMessage A custom message from the code that set the error.
* @param filename Filename of the error source
* @param function Function of the error source
* @param lineNumber Line number of the error source
*/
void ErrorBase::SetImaqError(int success, const wpi::Twine& contextMessage,
wpi::StringRef filename, wpi::StringRef function,
int lineNumber) const {
@@ -100,15 +73,6 @@ void ErrorBase::SetImaqError(int success, const wpi::Twine& contextMessage,
}
}
/**
* @brief Set the current error information associated with this sensor.
*
* @param code The error code
* @param contextMessage A custom message from the code that set the error.
* @param filename Filename of the error source
* @param function Function of the error source
* @param lineNumber Line number of the error source
*/
void ErrorBase::SetError(Error::Code code, const wpi::Twine& contextMessage,
wpi::StringRef filename, wpi::StringRef function,
int lineNumber) const {
@@ -125,19 +89,6 @@ void ErrorBase::SetError(Error::Code code, const wpi::Twine& contextMessage,
}
}
/**
* @brief Set the current error information associated with this sensor.
* Range versions use for initialization code.
*
* @param code The error code
* @param minRange The minimum allowed allocation range
* @param maxRange The maximum allowed allocation range
* @param requestedValue The requested value to allocate
* @param contextMessage A custom message from the code that set the error.
* @param filename Filename of the error source
* @param function Function of the error source
* @param lineNumber Line number of the error source
*/
void ErrorBase::SetErrorRange(Error::Code code, int32_t minRange,
int32_t maxRange, int32_t requestedValue,
const wpi::Twine& contextMessage,
@@ -160,15 +111,6 @@ void ErrorBase::SetErrorRange(Error::Code code, int32_t minRange,
}
}
/**
* @brief Set the current error information associated with this sensor.
*
* @param errorMessage The error message from WPIErrors.h
* @param contextMessage A custom message from the code that set the error.
* @param filename Filename of the error source
* @param function Function of the error source
* @param lineNumber Line number of the error source
*/
void ErrorBase::SetWPIError(const wpi::Twine& errorMessage, Error::Code code,
const wpi::Twine& contextMessage,
wpi::StringRef filename, wpi::StringRef function,
@@ -188,11 +130,6 @@ void ErrorBase::CloneError(const ErrorBase& rhs) const {
m_error.Clone(rhs.GetError());
}
/**
* @brief Check if the current error code represents a fatal error.
*
* @return true if the current error is fatal.
*/
bool ErrorBase::StatusIsFatal() const { return m_error.GetCode() < 0; }
void ErrorBase::SetGlobalError(Error::Code code,
@@ -221,9 +158,6 @@ void ErrorBase::SetGlobalWPIError(const wpi::Twine& errorMessage,
lineNumber, nullptr);
}
/**
* Retrieve the current global error.
*/
Error& ErrorBase::GetGlobalError() {
std::lock_guard<wpi::mutex> mutex(_globalErrorMutex);
return _globalError;

View File

@@ -12,13 +12,6 @@
using namespace frc;
/**
* Create a linear FIR or IIR filter.
*
* @param source The PIDSource object that is used to get values
* @param ffGains The "feed forward" or FIR gains
* @param fbGains The "feed back" or IIR gains
*/
LinearDigitalFilter::LinearDigitalFilter(PIDSource& source,
wpi::ArrayRef<double> ffGains,
wpi::ArrayRef<double> fbGains)
@@ -28,13 +21,6 @@ LinearDigitalFilter::LinearDigitalFilter(PIDSource& source,
m_inputGains(ffGains),
m_outputGains(fbGains) {}
/**
* Create a linear FIR or IIR filter.
*
* @param source The PIDSource object that is used to get values
* @param ffGains The "feed forward" or FIR gains
* @param fbGains The "feed back" or IIR gains
*/
LinearDigitalFilter::LinearDigitalFilter(std::shared_ptr<PIDSource> source,
wpi::ArrayRef<double> ffGains,
wpi::ArrayRef<double> fbGains)
@@ -44,17 +30,6 @@ LinearDigitalFilter::LinearDigitalFilter(std::shared_ptr<PIDSource> source,
m_inputGains(ffGains),
m_outputGains(fbGains) {}
/**
* Creates a one-pole IIR low-pass filter of the form:<br>
* y[n] = (1 - gain) * x[n] + gain * y[n-1]<br>
* where gain = e<sup>-dt / T</sup>, T is the time constant in seconds
*
* This filter is stable for time constants greater than zero.
*
* @param source The PIDSource object that is used to get values
* @param timeConstant The discrete-time time constant in seconds
* @param period The period in seconds between samples taken by the user
*/
LinearDigitalFilter LinearDigitalFilter::SinglePoleIIR(PIDSource& source,
double timeConstant,
double period) {
@@ -62,17 +37,6 @@ LinearDigitalFilter LinearDigitalFilter::SinglePoleIIR(PIDSource& source,
return LinearDigitalFilter(source, {1.0 - gain}, {-gain});
}
/**
* Creates a first-order high-pass filter of the form:<br>
* y[n] = gain * x[n] + (-gain) * x[n-1] + gain * y[n-1]<br>
* where gain = e<sup>-dt / T</sup>, T is the time constant in seconds
*
* This filter is stable for time constants greater than zero.
*
* @param source The PIDSource object that is used to get values
* @param timeConstant The discrete-time time constant in seconds
* @param period The period in seconds between samples taken by the user
*/
LinearDigitalFilter LinearDigitalFilter::HighPass(PIDSource& source,
double timeConstant,
double period) {
@@ -80,16 +44,6 @@ LinearDigitalFilter LinearDigitalFilter::HighPass(PIDSource& source,
return LinearDigitalFilter(source, {gain, -gain}, {-gain});
}
/**
* Creates a K-tap FIR moving average filter of the form:<br>
* y[n] = 1/k * (x[k] + x[k-1] + … + x[0])
*
* This filter is always stable.
*
* @param source The PIDSource object that is used to get values
* @param taps The number of samples to average over. Higher = smoother but
* slower
*/
LinearDigitalFilter LinearDigitalFilter::MovingAverage(PIDSource& source,
int taps) {
assert(taps > 0);
@@ -98,50 +52,18 @@ LinearDigitalFilter LinearDigitalFilter::MovingAverage(PIDSource& source,
return LinearDigitalFilter(source, gains, {});
}
/**
* Creates a one-pole IIR low-pass filter of the form:<br>
* y[n] = (1 - gain) * x[n] + gain * y[n-1]<br>
* where gain = e<sup>-dt / T</sup>, T is the time constant in seconds
*
* This filter is stable for time constants greater than zero.
*
* @param source The PIDSource object that is used to get values
* @param timeConstant The discrete-time time constant in seconds
* @param period The period in seconds between samples taken by the user
*/
LinearDigitalFilter LinearDigitalFilter::SinglePoleIIR(
std::shared_ptr<PIDSource> source, double timeConstant, double period) {
double gain = std::exp(-period / timeConstant);
return LinearDigitalFilter(std::move(source), {1.0 - gain}, {-gain});
}
/**
* Creates a first-order high-pass filter of the form:<br>
* y[n] = gain * x[n] + (-gain) * x[n-1] + gain * y[n-1]<br>
* where gain = e<sup>-dt / T</sup>, T is the time constant in seconds
*
* This filter is stable for time constants greater than zero.
*
* @param source The PIDSource object that is used to get values
* @param timeConstant The discrete-time time constant in seconds
* @param period The period in seconds between samples taken by the user
*/
LinearDigitalFilter LinearDigitalFilter::HighPass(
std::shared_ptr<PIDSource> source, double timeConstant, double period) {
double gain = std::exp(-period / timeConstant);
return LinearDigitalFilter(std::move(source), {gain, -gain}, {-gain});
}
/**
* Creates a K-tap FIR moving average filter of the form:<br>
* y[n] = 1/k * (x[k] + x[k-1] + … + x[0])
*
* This filter is always stable.
*
* @param source The PIDSource object that is used to get values
* @param taps The number of samples to average over. Higher = smoother but
* slower
*/
LinearDigitalFilter LinearDigitalFilter::MovingAverage(
std::shared_ptr<PIDSource> source, int taps) {
assert(taps > 0);
@@ -169,11 +91,6 @@ void LinearDigitalFilter::Reset() {
m_outputs.reset();
}
/**
* Calculates the next value of the filter
*
* @return The filtered value at this step
*/
double LinearDigitalFilter::PIDGet() {
double retVal = 0.0;

View File

@@ -13,54 +13,17 @@ using namespace frc;
constexpr double GearTooth::kGearToothThreshold;
/**
* Common code called by the constructors.
*/
void GearTooth::EnableDirectionSensing(bool directionSensitive) {
if (directionSensitive) {
SetPulseLengthMode(kGearToothThreshold);
}
}
/**
* Construct a GearTooth sensor given a channel.
*
* @param channel The DIO channel that the sensor is connected to.
* 0-9 are on-board, 10-25 are on the MXP.
* @param directionSensitive True to enable the pulse length decoding in
* hardware to specify count direction.
*/
GearTooth::GearTooth(int channel, bool directionSensitive) : Counter(channel) {
EnableDirectionSensing(directionSensitive);
SetName("GearTooth", channel);
}
/**
* Construct a GearTooth sensor given a digital input.
*
* This should be used when sharing digital inputs.
*
* @param source A pointer to the existing DigitalSource object
* (such as a DigitalInput)
* @param directionSensitive True to enable the pulse length decoding in
* hardware to specify count direction.
*/
GearTooth::GearTooth(DigitalSource* source, bool directionSensitive)
: Counter(source) {
EnableDirectionSensing(directionSensitive);
SetName("GearTooth", source->GetChannel());
}
/**
* Construct a GearTooth sensor given a digital input.
*
* This should be used when sharing digital inputs.
*
* @param source A reference to the existing DigitalSource object
* (such as a DigitalInput)
* @param directionSensitive True to enable the pulse length decoding in
* hardware to specify count direction.
*/
GearTooth::GearTooth(std::shared_ptr<DigitalSource> source,
bool directionSensitive)
: Counter(source) {
@@ -68,6 +31,12 @@ GearTooth::GearTooth(std::shared_ptr<DigitalSource> source,
SetName("GearTooth", source->GetChannel());
}
void GearTooth::EnableDirectionSensing(bool directionSensitive) {
if (directionSensitive) {
SetPulseLengthMode(kGearToothThreshold);
}
}
void GearTooth::InitSendable(SendableBuilder& builder) {
Counter::InitSendable(builder);
builder.SetSmartDashboardType("Gear Tooth");

View File

@@ -21,125 +21,44 @@ GenericHID::GenericHID(int port) : m_ds(DriverStation::GetInstance()) {
m_port = port;
}
/**
* Get the button value (starting at button 1).
*
* The buttons are returned in a single 16 bit value with one bit representing
* the state of each button. The appropriate button is returned as a boolean
* value.
*
* @param button The button number to be read (starting at 1)
* @return The state of the button.
*/
bool GenericHID::GetRawButton(int button) const {
return m_ds.GetStickButton(m_port, button);
}
/**
* Whether the button was pressed since the last check. Button indexes begin at
* 1.
*
* @param button The button index, beginning at 1.
* @return Whether the button was pressed since the last check.
*/
bool GenericHID::GetRawButtonPressed(int button) {
return m_ds.GetStickButtonPressed(m_port, button);
}
/**
* Whether the button was released since the last check. Button indexes begin at
* 1.
*
* @param button The button index, beginning at 1.
* @return Whether the button was released since the last check.
*/
bool GenericHID::GetRawButtonReleased(int button) {
return m_ds.GetStickButtonReleased(m_port, button);
}
/**
* Get the value of the axis.
*
* @param axis The axis to read, starting at 0.
* @return The value of the axis.
*/
double GenericHID::GetRawAxis(int axis) const {
return m_ds.GetStickAxis(m_port, axis);
}
/**
* Get the angle in degrees of a POV on the HID.
*
* The POV angles start at 0 in the up direction, and increase clockwise
* (e.g. right is 90, upper-left is 315).
*
* @param pov The index of the POV to read (starting at 0)
* @return the angle of the POV in degrees, or -1 if the POV is not pressed.
*/
int GenericHID::GetPOV(int pov) const { return m_ds.GetStickPOV(m_port, pov); }
/**
* Get the number of axes for the HID.
*
* @return the number of axis for the current HID
*/
int GenericHID::GetAxisCount() const { return m_ds.GetStickAxisCount(m_port); }
/**
* Get the number of POVs for the HID.
*
* @return the number of POVs for the current HID
*/
int GenericHID::GetPOVCount() const { return m_ds.GetStickPOVCount(m_port); }
/**
* Get the number of buttons for the HID.
*
* @return the number of buttons on the current HID
*/
int GenericHID::GetButtonCount() const {
return m_ds.GetStickButtonCount(m_port);
}
/**
* Get the type of the HID.
*
* @return the type of the HID.
*/
GenericHID::HIDType GenericHID::GetType() const {
return static_cast<HIDType>(m_ds.GetJoystickType(m_port));
}
/**
* Get the name of the HID.
*
* @return the name of the HID.
*/
std::string GenericHID::GetName() const { return m_ds.GetJoystickName(m_port); }
/**
* Get the axis type of a joystick axis.
*
* @return the axis type of a joystick axis.
*/
int GenericHID::GetAxisType(int axis) const {
return m_ds.GetJoystickAxisType(m_port, axis);
}
/**
* Get the port number of the HID.
*
* @return The port number of the HID.
*/
int GenericHID::GetPort() const { return m_port; }
/**
* Set a single HID output value for the HID.
*
* @param outputNumber The index of the output to set (1-32)
* @param value The value to set the output to
*/
void GenericHID::SetOutput(int outputNumber, bool value) {
m_outputs =
(m_outputs & ~(1 << (outputNumber - 1))) | (value << (outputNumber - 1));
@@ -147,24 +66,11 @@ void GenericHID::SetOutput(int outputNumber, bool value) {
HAL_SetJoystickOutputs(m_port, m_outputs, m_leftRumble, m_rightRumble);
}
/**
* Set all output values for the HID.
*
* @param value The 32 bit output value (1 bit for each output)
*/
void GenericHID::SetOutputs(int value) {
m_outputs = value;
HAL_SetJoystickOutputs(m_port, m_outputs, m_leftRumble, m_rightRumble);
}
/**
* Set the rumble output for the HID.
*
* The DS currently supports 2 rumble values, left rumble and right rumble.
*
* @param type Which rumble value to set
* @param value The normalized value (0 to 1) to set the rumble to
*/
void GenericHID::SetRumble(RumbleType type, double value) {
if (value < 0)
value = 0;

View File

@@ -12,12 +12,6 @@
using namespace frc;
/**
* Get the PIDOutput for the PIDSource base object. Can be set to return
* angle or rate using SetPIDSourceType(). Defaults to angle.
*
* @return The PIDOutput (angle or rate, defaults to angle)
*/
double GyroBase::PIDGet() {
switch (GetPIDSourceType()) {
case PIDSourceType::kRate:

View File

@@ -14,12 +14,6 @@
using namespace frc;
/**
* Constructor.
*
* @param port The I2C port to which the device is connected.
* @param deviceAddress The address of the device on the I2C bus.
*/
I2C::I2C(Port port, int deviceAddress)
: m_port(static_cast<HAL_I2CPort>(port)), m_deviceAddress(deviceAddress) {
int32_t status = 0;
@@ -29,23 +23,8 @@ I2C::I2C(Port port, int deviceAddress)
HAL_Report(HALUsageReporting::kResourceType_I2C, deviceAddress);
}
/**
* Destructor.
*/
I2C::~I2C() { HAL_CloseI2C(m_port); }
/**
* Generic transaction.
*
* This is a lower-level interface to the I2C hardware giving you more control
* over each transaction.
*
* @param dataToSend Buffer of data to send as part of the transaction.
* @param sendSize Number of bytes to send as part of the transaction.
* @param dataReceived Buffer to read data into.
* @param receiveSize Number of bytes to read from the device.
* @return Transfer Aborted... false for success, true for aborted.
*/
bool I2C::Transaction(uint8_t* dataToSend, int sendSize, uint8_t* dataReceived,
int receiveSize) {
int32_t status = 0;
@@ -55,27 +34,8 @@ bool I2C::Transaction(uint8_t* dataToSend, int sendSize, uint8_t* dataReceived,
return status < 0;
}
/**
* Attempt to address a device on the I2C bus.
*
* This allows you to figure out if there is a device on the I2C bus that
* responds to the address specified in the constructor.
*
* @return Transfer Aborted... false for success, true for aborted.
*/
bool I2C::AddressOnly() { return Transaction(nullptr, 0, nullptr, 0); }
/**
* Execute a write transaction with the device.
*
* Write a single byte to a register on a device and wait until the
* transaction is complete.
*
* @param registerAddress The address of the register on the device to be
* written.
* @param data The byte to write to the register on the device.
* @return Transfer Aborted... false for success, true for aborted.
*/
bool I2C::Write(int registerAddress, uint8_t data) {
uint8_t buffer[2];
buffer[0] = registerAddress;
@@ -85,35 +45,12 @@ bool I2C::Write(int registerAddress, uint8_t data) {
return status < 0;
}
/**
* Execute a bulk write transaction with the device.
*
* Write multiple bytes to a device and wait until the
* transaction is complete.
*
* @param data The data to write to the register on the device.
* @param count The number of bytes to be written.
* @return Transfer Aborted... false for success, true for aborted.
*/
bool I2C::WriteBulk(uint8_t* data, int count) {
int32_t status = 0;
status = HAL_WriteI2C(m_port, m_deviceAddress, data, count);
return status < 0;
}
/**
* Execute a read transaction with the device.
*
* Read bytes from a device.
* Most I2C devices will auto-increment the register pointer internally allowing
* you to read consecutive registers on a device in a single transaction.
*
* @param registerAddress The register to read first in the transaction.
* @param count The number of bytes to read in the transaction.
* @param buffer A pointer to the array of bytes to store the data
* read from the device.
* @return Transfer Aborted... false for success, true for aborted.
*/
bool I2C::Read(int registerAddress, int count, uint8_t* buffer) {
if (count < 1) {
wpi_setWPIErrorWithContext(ParameterOutOfRange, "count");
@@ -127,17 +64,6 @@ bool I2C::Read(int registerAddress, int count, uint8_t* buffer) {
return Transaction(&regAddr, sizeof(regAddr), buffer, count);
}
/**
* Execute a read only transaction with the device.
*
* Read bytes from a device. This method does not write any data to prompt the
* device.
*
* @param buffer A pointer to the array of bytes to store the data read from
* the device.
* @param count The number of bytes to read in the transaction.
* @return Transfer Aborted... false for success, true for aborted.
*/
bool I2C::ReadOnly(int count, uint8_t* buffer) {
if (count < 1) {
wpi_setWPIErrorWithContext(ParameterOutOfRange, "count");
@@ -150,21 +76,6 @@ bool I2C::ReadOnly(int count, uint8_t* buffer) {
return HAL_ReadI2C(m_port, m_deviceAddress, buffer, count) < 0;
}
/**
* Verify that a device's registers contain expected values.
*
* Most devices will have a set of registers that contain a known value that
* can be used to identify them. This allows an I2C device driver to easily
* verify that the device contains the expected value.
*
* @pre The device must support and be configured to use register
* auto-increment.
*
* @param registerAddress The base register to start reading from the device.
* @param count The size of the field to be verified.
* @param expected A buffer containing the values expected from the
* device.
*/
bool I2C::VerifySensor(int registerAddress, int count,
const uint8_t* expected) {
// TODO: Make use of all 7 read bytes

View File

@@ -14,14 +14,6 @@
using namespace frc;
/**
* Request one of the 8 interrupts asynchronously on this digital input.
*
* Request interrupts in asynchronous mode where the user's interrupt handler
* will be called when the interrupt fires. Users that want control over the
* thread priority should use the synchronous method with their own spawned
* thread. The default is interrupt on rising edges only.
*/
void InterruptableSensorBase::RequestInterrupts(
HAL_InterruptHandlerFunction handler, void* param) {
if (StatusIsFatal()) return;
@@ -40,13 +32,6 @@ void InterruptableSensorBase::RequestInterrupts(
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Request one of the 8 interrupts synchronously on this digital input.
*
* Request interrupts in synchronous mode where the user program will have to
* explicitly wait for the interrupt to occur using WaitForInterrupt.
* The default is interrupt on rising edges only.
*/
void InterruptableSensorBase::RequestInterrupts() {
if (StatusIsFatal()) return;
@@ -63,19 +48,6 @@ void InterruptableSensorBase::RequestInterrupts() {
SetUpSourceEdge(true, false);
}
void InterruptableSensorBase::AllocateInterrupts(bool watcher) {
wpi_assert(m_interrupt == HAL_kInvalidHandle);
// Expects the calling leaf class to allocate an interrupt index.
int32_t status = 0;
m_interrupt = HAL_InitializeInterrupts(watcher, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Cancel interrupts on this device.
*
* This deallocates all the chipobject structures and disables any interrupts.
*/
void InterruptableSensorBase::CancelInterrupts() {
if (StatusIsFatal()) return;
wpi_assert(m_interrupt != HAL_kInvalidHandle);
@@ -85,18 +57,6 @@ void InterruptableSensorBase::CancelInterrupts() {
m_interrupt = HAL_kInvalidHandle;
}
/**
* In synchronous mode, wait for the defined interrupt to occur.
*
* You should <b>NOT</b> attempt to read the sensor from another thread while
* waiting for an interrupt. This is not threadsafe, and can cause memory
* corruption
*
* @param timeout Timeout in seconds
* @param ignorePrevious If true, ignore interrupts that happened before
* WaitForInterrupt was called.
* @return What interrupts fired
*/
InterruptableSensorBase::WaitResult InterruptableSensorBase::WaitForInterrupt(
double timeout, bool ignorePrevious) {
if (StatusIsFatal()) return InterruptableSensorBase::kTimeout;
@@ -116,13 +76,6 @@ InterruptableSensorBase::WaitResult InterruptableSensorBase::WaitForInterrupt(
return static_cast<WaitResult>(falling | rising);
}
/**
* Enable interrupts to occur on this input.
*
* Interrupts are disabled when the RequestInterrupt call is made. This gives
* time to do the setup of the other options before starting to field
* interrupts.
*/
void InterruptableSensorBase::EnableInterrupts() {
if (StatusIsFatal()) return;
wpi_assert(m_interrupt != HAL_kInvalidHandle);
@@ -131,9 +84,6 @@ void InterruptableSensorBase::EnableInterrupts() {
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Disable Interrupts without without deallocating structures.
*/
void InterruptableSensorBase::DisableInterrupts() {
if (StatusIsFatal()) return;
wpi_assert(m_interrupt != HAL_kInvalidHandle);
@@ -142,15 +92,6 @@ void InterruptableSensorBase::DisableInterrupts() {
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Return the timestamp for the rising interrupt that occurred most recently.
*
* This is in the same time domain as GetClock().
* The rising-edge interrupt should be enabled with
* {@link #DigitalInput.SetUpSourceEdge}
*
* @return Timestamp in seconds since boot.
*/
double InterruptableSensorBase::ReadRisingTimestamp() {
if (StatusIsFatal()) return 0.0;
wpi_assert(m_interrupt != HAL_kInvalidHandle);
@@ -160,15 +101,6 @@ double InterruptableSensorBase::ReadRisingTimestamp() {
return timestamp;
}
/**
* Return the timestamp for the falling interrupt that occurred most recently.
*
* This is in the same time domain as GetClock().
* The falling-edge interrupt should be enabled with
* {@link #DigitalInput.SetUpSourceEdge}
*
* @return Timestamp in seconds since boot.
*/
double InterruptableSensorBase::ReadFallingTimestamp() {
if (StatusIsFatal()) return 0.0;
wpi_assert(m_interrupt != HAL_kInvalidHandle);
@@ -178,12 +110,6 @@ double InterruptableSensorBase::ReadFallingTimestamp() {
return timestamp;
}
/**
* Set which edge to trigger interrupts on
*
* @param risingEdge true to interrupt on rising edge
* @param fallingEdge true to interrupt on falling edge
*/
void InterruptableSensorBase::SetUpSourceEdge(bool risingEdge,
bool fallingEdge) {
if (StatusIsFatal()) return;
@@ -199,3 +125,11 @@ void InterruptableSensorBase::SetUpSourceEdge(bool risingEdge,
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
}
void InterruptableSensorBase::AllocateInterrupts(bool watcher) {
wpi_assert(m_interrupt == HAL_kInvalidHandle);
// Expects the calling leaf class to allocate an interrupt index.
int32_t status = 0;
m_interrupt = HAL_InitializeInterrupts(watcher, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}

View File

@@ -18,12 +18,6 @@ IterativeRobot::IterativeRobot() {
HALUsageReporting::kFramework_Iterative);
}
/**
* Provide an alternate "main loop" via StartCompetition().
*
* This specific StartCompetition() implements "main loop" behaviour synced with
* the DS packets.
*/
void IterativeRobot::StartCompetition() {
RobotInit();

View File

@@ -18,69 +18,26 @@
using namespace frc;
/**
* Robot-wide initialization code should go here.
*
* Users should override this method for default Robot-wide initialization which
* will be called when the robot is first powered on. It will be called exactly
* one time.
*
* Warning: the Driver Station "Robot Code" light and FMS "Robot Ready"
* indicators will be off until RobotInit() exits. Code in RobotInit() that
* waits for enable will cause the robot to never indicate that the code is
* ready, causing the robot to be bypassed in a match.
*/
void IterativeRobotBase::RobotInit() {
wpi::outs() << "Default " << __FUNCTION__ << "() method... Overload me!\n";
}
/**
* Initialization code for disabled mode should go here.
*
* Users should override this method for initialization code which will be
* called each time
* the robot enters disabled mode.
*/
void IterativeRobotBase::DisabledInit() {
wpi::outs() << "Default " << __FUNCTION__ << "() method... Overload me!\n";
}
/**
* Initialization code for autonomous mode should go here.
*
* Users should override this method for initialization code which will be
* called each time the robot enters autonomous mode.
*/
void IterativeRobotBase::AutonomousInit() {
wpi::outs() << "Default " << __FUNCTION__ << "() method... Overload me!\n";
}
/**
* Initialization code for teleop mode should go here.
*
* Users should override this method for initialization code which will be
* called each time the robot enters teleop mode.
*/
void IterativeRobotBase::TeleopInit() {
wpi::outs() << "Default " << __FUNCTION__ << "() method... Overload me!\n";
}
/**
* Initialization code for test mode should go here.
*
* Users should override this method for initialization code which will be
* called each time the robot enters test mode.
*/
void IterativeRobotBase::TestInit() {
wpi::outs() << "Default " << __FUNCTION__ << "() method... Overload me!\n";
}
/**
* Periodic code for all modes should go here.
*
* This function is called each time a new packet is received from the driver
* station.
*/
void IterativeRobotBase::RobotPeriodic() {
static bool firstRun = true;
if (firstRun) {
@@ -89,13 +46,6 @@ void IterativeRobotBase::RobotPeriodic() {
}
}
/**
* Periodic code for disabled mode should go here.
*
* Users should override this method for code which will be called each time a
* new packet is received from the driver station and the robot is in disabled
* mode.
*/
void IterativeRobotBase::DisabledPeriodic() {
static bool firstRun = true;
if (firstRun) {
@@ -104,13 +54,6 @@ void IterativeRobotBase::DisabledPeriodic() {
}
}
/**
* Periodic code for autonomous mode should go here.
*
* Users should override this method for code which will be called each time a
* new packet is received from the driver station and the robot is in autonomous
* mode.
*/
void IterativeRobotBase::AutonomousPeriodic() {
static bool firstRun = true;
if (firstRun) {
@@ -119,13 +62,6 @@ void IterativeRobotBase::AutonomousPeriodic() {
}
}
/**
* Periodic code for teleop mode should go here.
*
* Users should override this method for code which will be called each time a
* new packet is received from the driver station and the robot is in teleop
* mode.
*/
void IterativeRobotBase::TeleopPeriodic() {
static bool firstRun = true;
if (firstRun) {
@@ -134,12 +70,6 @@ void IterativeRobotBase::TeleopPeriodic() {
}
}
/**
* Periodic code for test mode should go here.
*
* Users should override this method for code which will be called each time a
* new packet is received from the driver station and the robot is in test mode.
*/
void IterativeRobotBase::TestPeriodic() {
static bool firstRun = true;
if (firstRun) {

View File

@@ -11,15 +11,8 @@
using namespace frc;
/**
* Constructor for a Jaguar connected via PWM.
*
* @param channel The PWM channel that the Jaguar is attached to. 0-9 are
* on-board, 10-19 are on the MXP port
*/
Jaguar::Jaguar(int channel) : PWMSpeedController(channel) {
/**
* Input profile defined by Luminary Micro.
/* Input profile defined by Luminary Micro.
*
* Full reverse ranges from 0.671325ms to 0.6972211ms
* Proportional reverse ranges from 0.6972211ms to 1.4482078ms

View File

@@ -18,14 +18,6 @@ using namespace frc;
constexpr double kPi = 3.14159265358979323846;
/**
* Construct an instance of a joystick.
*
* The joystick index is the USB port on the Driver Station.
*
* @param port The port on the Driver Station that the joystick is plugged into
* (0-5).
*/
Joystick::Joystick(int port) : GenericHID(port) {
m_axes[Axis::kX] = kDefaultXChannel;
m_axes[Axis::kY] = kDefaultYChannel;
@@ -36,149 +28,48 @@ Joystick::Joystick(int port) : GenericHID(port) {
HAL_Report(HALUsageReporting::kResourceType_Joystick, port);
}
/**
* Set the channel associated with a specified axis.
*
* @param axis The axis to set the channel for.
* @param channel The channel to set the axis to.
*/
void Joystick::SetAxisChannel(AxisType axis, int channel) {
m_axes[axis] = channel;
}
/**
* Set the channel associated with the X axis.
*
* @param channel The channel to set the axis to.
*/
void Joystick::SetXChannel(int channel) { m_axes[Axis::kX] = channel; }
/**
* Set the channel associated with the Y axis.
*
* @param axis The axis to set the channel for.
* @param channel The channel to set the axis to.
*/
void Joystick::SetYChannel(int channel) { m_axes[Axis::kY] = channel; }
/**
* Set the channel associated with the Z axis.
*
* @param axis The axis to set the channel for.
* @param channel The channel to set the axis to.
*/
void Joystick::SetZChannel(int channel) { m_axes[Axis::kZ] = channel; }
/**
* Set the channel associated with the twist axis.
*
* @param axis The axis to set the channel for.
* @param channel The channel to set the axis to.
*/
void Joystick::SetTwistChannel(int channel) { m_axes[Axis::kTwist] = channel; }
/**
* Set the channel associated with the throttle axis.
*
* @param axis The axis to set the channel for.
* @param channel The channel to set the axis to.
*/
void Joystick::SetThrottleChannel(int channel) {
m_axes[Axis::kThrottle] = channel;
}
/**
* Get the channel currently associated with the X axis.
*
* @return The channel for the axis.
*/
void Joystick::SetAxisChannel(AxisType axis, int channel) {
m_axes[axis] = channel;
}
int Joystick::GetXChannel() const { return m_axes[Axis::kX]; }
/**
* Get the channel currently associated with the Y axis.
*
* @return The channel for the axis.
*/
int Joystick::GetYChannel() const { return m_axes[Axis::kY]; }
/**
* Get the channel currently associated with the Z axis.
*
* @return The channel for the axis.
*/
int Joystick::GetZChannel() const { return m_axes[Axis::kZ]; }
/**
* Get the channel currently associated with the twist axis.
*
* @return The channel for the axis.
*/
int Joystick::GetTwistChannel() const { return m_axes[Axis::kTwist]; }
/**
* Get the channel currently associated with the throttle axis.
*
* @return The channel for the axis.
*/
int Joystick::GetThrottleChannel() const { return m_axes[Axis::kThrottle]; }
/**
* Get the X value of the joystick.
*
* This depends on the mapping of the joystick connected to the current port.
*
* @param hand This parameter is ignored for the Joystick class and is only
* here to complete the GenericHID interface.
*/
double Joystick::GetX(JoystickHand hand) const {
return GetRawAxis(m_axes[Axis::kX]);
}
/**
* Get the Y value of the joystick.
*
* This depends on the mapping of the joystick connected to the current port.
*
* @param hand This parameter is ignored for the Joystick class and is only
* here to complete the GenericHID interface.
*/
double Joystick::GetY(JoystickHand hand) const {
return GetRawAxis(m_axes[Axis::kY]);
}
/**
* Get the Z value of the current joystick.
*
* This depends on the mapping of the joystick connected to the current port.
*/
double Joystick::GetZ() const { return GetRawAxis(m_axes[Axis::kZ]); }
/**
* Get the twist value of the current joystick.
*
* This depends on the mapping of the joystick connected to the current port.
*/
double Joystick::GetTwist() const { return GetRawAxis(m_axes[Axis::kTwist]); }
/**
* Get the throttle value of the current joystick.
*
* This depends on the mapping of the joystick connected to the current port.
*/
double Joystick::GetThrottle() const {
return GetRawAxis(m_axes[Axis::kThrottle]);
}
/**
* For the current joystick, return the axis determined by the argument.
*
* This is for cases where the joystick axis is returned programatically,
* otherwise one of the previous functions would be preferable (for example
* GetX()).
*
* @param axis The axis to read.
* @return The value of the axis.
*/
double Joystick::GetAxis(AxisType axis) const {
switch (axis) {
case kXAxis:
@@ -197,54 +88,20 @@ double Joystick::GetAxis(AxisType axis) const {
}
}
/**
* Read the state of the trigger on the joystick.
*
* Look up which button has been assigned to the trigger and read its state.
*
* @return The state of the trigger.
*/
bool Joystick::GetTrigger() const { return GetRawButton(Button::kTrigger); }
/**
* Whether the trigger was pressed since the last check.
*
* @return Whether the button was pressed since the last check.
*/
bool Joystick::GetTriggerPressed() {
return GetRawButtonPressed(Button::kTrigger);
}
/**
* Whether the trigger was released since the last check.
*
* @return Whether the button was released since the last check.
*/
bool Joystick::GetTriggerReleased() {
return GetRawButtonReleased(Button::kTrigger);
}
/**
* Read the state of the top button on the joystick.
*
* Look up which button has been assigned to the top and read its state.
*
* @return The state of the top button.
*/
bool Joystick::GetTop() const { return GetRawButton(Button::kTop); }
/**
* Whether the top button was pressed since the last check.
*
* @return Whether the button was pressed since the last check.
*/
bool Joystick::GetTopPressed() { return GetRawButtonPressed(Button::kTop); }
/**
* Whether the top button was released since the last check.
*
* @return Whether the button was released since the last check.
*/
bool Joystick::GetTopReleased() { return GetRawButtonReleased(Button::kTop); }
Joystick* Joystick::GetStickForPort(int port) {
@@ -258,45 +115,19 @@ Joystick* Joystick::GetStickForPort(int port) {
return stick;
}
/**
* Get buttons based on an enumerated type.
*
* The button type will be looked up in the list of buttons and then read.
*
* @param button The type of button to read.
* @return The state of the button.
*/
bool Joystick::GetButton(ButtonType button) const {
int temp = button;
return GetRawButton(static_cast<Button>(temp));
}
/**
* Get the magnitude of the direction vector formed by the joystick's
* current position relative to its origin.
*
* @return The magnitude of the direction vector
*/
double Joystick::GetMagnitude() const {
return std::sqrt(std::pow(GetX(), 2) + std::pow(GetY(), 2));
}
/**
* Get the direction of the vector formed by the joystick and its origin
* in radians.
*
* @return The direction of the vector in radians
*/
double Joystick::GetDirectionRadians() const {
return std::atan2(GetX(), -GetY());
}
/**
* Get the direction of the vector formed by the joystick and its origin
* in degrees.
*
* @return The direction of the vector in degrees
*/
double Joystick::GetDirectionDegrees() const {
return (180 / kPi) * GetDirectionRadians();
}

View File

@@ -55,34 +55,122 @@ LiveWindow::Impl::Impl()
enabledEntry = statusTable->GetEntry("LW Enabled");
}
/**
* Get an instance of the LiveWindow main class.
*
* This is a singleton to guarantee that there is only a single instance
* regardless of how many times GetInstance is called.
*/
LiveWindow* LiveWindow::GetInstance() {
static LiveWindow instance;
return &instance;
}
/**
* LiveWindow constructor.
*
* Allocate the necessary tables.
*/
LiveWindow::LiveWindow() : m_impl(new Impl) {}
void LiveWindow::Run() { UpdateValues(); }
void LiveWindow::AddSensor(const wpi::Twine& subsystem, const wpi::Twine& name,
Sendable* component) {
Add(component);
component->SetName(subsystem, name);
}
void LiveWindow::AddSensor(const wpi::Twine& subsystem, const wpi::Twine& name,
Sendable& component) {
Add(&component);
component.SetName(subsystem, name);
}
void LiveWindow::AddSensor(const wpi::Twine& subsystem, const wpi::Twine& name,
std::shared_ptr<Sendable> component) {
Add(component);
component->SetName(subsystem, name);
}
void LiveWindow::AddActuator(const wpi::Twine& subsystem,
const wpi::Twine& name, Sendable* component) {
Add(component);
component->SetName(subsystem, name);
}
void LiveWindow::AddActuator(const wpi::Twine& subsystem,
const wpi::Twine& name, Sendable& component) {
Add(&component);
component.SetName(subsystem, name);
}
void LiveWindow::AddActuator(const wpi::Twine& subsystem,
const wpi::Twine& name,
std::shared_ptr<Sendable> component) {
Add(component);
component->SetName(subsystem, name);
}
void LiveWindow::AddSensor(const wpi::Twine& type, int channel,
Sendable* component) {
Add(component);
component->SetName("Ungrouped",
type + Twine('[') + Twine(channel) + Twine(']'));
}
void LiveWindow::AddActuator(const wpi::Twine& type, int channel,
Sendable* component) {
Add(component);
component->SetName("Ungrouped",
type + Twine('[') + Twine(channel) + Twine(']'));
}
void LiveWindow::AddActuator(const wpi::Twine& type, int module, int channel,
Sendable* component) {
Add(component);
component->SetName("Ungrouped", type + Twine('[') + Twine(module) +
Twine(',') + Twine(channel) + Twine(']'));
}
void LiveWindow::Add(std::shared_ptr<Sendable> sendable) {
std::lock_guard<wpi::mutex> lock(m_impl->mutex);
auto& comp = m_impl->components[sendable.get()];
comp.sendable = sendable;
}
void LiveWindow::Add(Sendable* sendable) {
Add(std::shared_ptr<Sendable>(sendable, NullDeleter<Sendable>()));
}
void LiveWindow::AddChild(Sendable* parent, std::shared_ptr<Sendable> child) {
AddChild(parent, child.get());
}
void LiveWindow::AddChild(Sendable* parent, void* child) {
std::lock_guard<wpi::mutex> lock(m_impl->mutex);
auto& comp = m_impl->components[child];
comp.parent = parent;
comp.telemetryEnabled = false;
}
void LiveWindow::Remove(Sendable* sendable) {
std::lock_guard<wpi::mutex> lock(m_impl->mutex);
m_impl->components.erase(sendable);
}
void LiveWindow::EnableTelemetry(Sendable* sendable) {
std::lock_guard<wpi::mutex> lock(m_impl->mutex);
// Re-enable global setting in case DisableAllTelemetry() was called.
m_impl->telemetryEnabled = true;
auto i = m_impl->components.find(sendable);
if (i != m_impl->components.end()) i->getSecond().telemetryEnabled = true;
}
void LiveWindow::DisableTelemetry(Sendable* sendable) {
std::lock_guard<wpi::mutex> lock(m_impl->mutex);
auto i = m_impl->components.find(sendable);
if (i != m_impl->components.end()) i->getSecond().telemetryEnabled = false;
}
void LiveWindow::DisableAllTelemetry() {
std::lock_guard<wpi::mutex> lock(m_impl->mutex);
m_impl->telemetryEnabled = false;
for (auto& i : m_impl->components) i.getSecond().telemetryEnabled = false;
}
bool LiveWindow::IsEnabled() const {
std::lock_guard<wpi::mutex> lock(m_impl->mutex);
return m_impl->liveWindowEnabled;
}
/**
* Change the enabled status of LiveWindow.
*
* If it changes to enabled, start livewindow running otherwise stop it
*/
void LiveWindow::SetEnabled(bool enabled) {
std::lock_guard<wpi::mutex> lock(m_impl->mutex);
if (m_impl->liveWindowEnabled == enabled) return;
@@ -101,214 +189,6 @@ void LiveWindow::SetEnabled(bool enabled) {
m_impl->enabledEntry.SetBoolean(enabled);
}
/**
* @name AddSensor(subsystem, name, component)
*
* Add a Sensor associated with the subsystem and call it by the given name.
*
* @param subsystem The subsystem this component is part of.
* @param name The name of this component.
* @param component A Sendable component that represents a sensor.
*/
//@{
/**
* @brief Use a STL smart pointer to share ownership of component.
* @deprecated Use Sendable::SetName() instead.
*/
void LiveWindow::AddSensor(const wpi::Twine& subsystem, const wpi::Twine& name,
std::shared_ptr<Sendable> component) {
Add(component);
component->SetName(subsystem, name);
}
/**
* @brief Pass a reference to LiveWindow and retain ownership of the component.
* @deprecated Use Sendable::SetName() instead.
*/
void LiveWindow::AddSensor(const wpi::Twine& subsystem, const wpi::Twine& name,
Sendable& component) {
Add(&component);
component.SetName(subsystem, name);
}
/**
* @brief Use a raw pointer to the LiveWindow.
* @deprecated Use Sendable::SetName() instead.
*/
void LiveWindow::AddSensor(const wpi::Twine& subsystem, const wpi::Twine& name,
Sendable* component) {
Add(component);
component->SetName(subsystem, name);
}
//@}
/**
* @name AddActuator(subsystem, name, component)
*
* Add an Actuator associated with the subsystem and call it by the given name.
* @deprecated Use Sendable::SetName() instead.
*
* @param subsystem The subsystem this component is part of.
* @param name The name of this component.
* @param component A Sendable component that represents a actuator.
*/
//@{
/**
* @brief Use a STL smart pointer to share ownership of component.
*/
void LiveWindow::AddActuator(const wpi::Twine& subsystem,
const wpi::Twine& name,
std::shared_ptr<Sendable> component) {
Add(component);
component->SetName(subsystem, name);
}
/**
* @brief Pass a reference to LiveWindow and retain ownership of the component.
* @deprecated Use Sendable::SetName() instead.
*/
void LiveWindow::AddActuator(const wpi::Twine& subsystem,
const wpi::Twine& name, Sendable& component) {
Add(&component);
component.SetName(subsystem, name);
}
/**
* @brief Use a raw pointer to the LiveWindow.
* @deprecated Use Sendable::SetName() instead.
*/
void LiveWindow::AddActuator(const wpi::Twine& subsystem,
const wpi::Twine& name, Sendable* component) {
Add(component);
component->SetName(subsystem, name);
}
//@}
/**
* Meant for internal use in other WPILib classes.
* @deprecated Use SendableBase::SetName() instead.
*/
void LiveWindow::AddSensor(const wpi::Twine& type, int channel,
Sendable* component) {
Add(component);
component->SetName("Ungrouped",
type + Twine('[') + Twine(channel) + Twine(']'));
}
/**
* Meant for internal use in other WPILib classes.
* @deprecated Use SendableBase::SetName() instead.
*/
void LiveWindow::AddActuator(const wpi::Twine& type, int channel,
Sendable* component) {
Add(component);
component->SetName("Ungrouped",
type + Twine('[') + Twine(channel) + Twine(']'));
}
/**
* Meant for internal use in other WPILib classes.
* @deprecated Use SendableBase::SetName() instead.
*/
void LiveWindow::AddActuator(const wpi::Twine& type, int module, int channel,
Sendable* component) {
Add(component);
component->SetName("Ungrouped", type + Twine('[') + Twine(module) +
Twine(',') + Twine(channel) + Twine(']'));
}
/**
* Add a component to the LiveWindow.
*
* @param sendable component to add
*/
void LiveWindow::Add(std::shared_ptr<Sendable> sendable) {
std::lock_guard<wpi::mutex> lock(m_impl->mutex);
auto& comp = m_impl->components[sendable.get()];
comp.sendable = sendable;
}
/**
* Add a component to the LiveWindow.
*
* @param sendable component to add
*/
void LiveWindow::Add(Sendable* sendable) {
Add(std::shared_ptr<Sendable>(sendable, NullDeleter<Sendable>()));
}
/**
* Add a child component to a component.
*
* @param parent parent component
* @param child child component
*/
void LiveWindow::AddChild(Sendable* parent, std::shared_ptr<Sendable> child) {
AddChild(parent, child.get());
}
/**
* Add a child component to a component.
*
* @param parent parent component
* @param child child component
*/
void LiveWindow::AddChild(Sendable* parent, void* child) {
std::lock_guard<wpi::mutex> lock(m_impl->mutex);
auto& comp = m_impl->components[child];
comp.parent = parent;
comp.telemetryEnabled = false;
}
/**
* Remove the component from the LiveWindow.
*
* @param sendable component to remove
*/
void LiveWindow::Remove(Sendable* sendable) {
std::lock_guard<wpi::mutex> lock(m_impl->mutex);
m_impl->components.erase(sendable);
}
/**
* Enable telemetry for a single component.
*
* @param sendable component
*/
void LiveWindow::EnableTelemetry(Sendable* sendable) {
std::lock_guard<wpi::mutex> lock(m_impl->mutex);
// Re-enable global setting in case DisableAllTelemetry() was called.
m_impl->telemetryEnabled = true;
auto i = m_impl->components.find(sendable);
if (i != m_impl->components.end()) i->getSecond().telemetryEnabled = true;
}
/**
* Disable telemetry for a single component.
*
* @param sendable component
*/
void LiveWindow::DisableTelemetry(Sendable* sendable) {
std::lock_guard<wpi::mutex> lock(m_impl->mutex);
auto i = m_impl->components.find(sendable);
if (i != m_impl->components.end()) i->getSecond().telemetryEnabled = false;
}
/**
* Disable ALL telemetry.
*/
void LiveWindow::DisableAllTelemetry() {
std::lock_guard<wpi::mutex> lock(m_impl->mutex);
m_impl->telemetryEnabled = false;
for (auto& i : m_impl->components) i.getSecond().telemetryEnabled = false;
}
/**
* Tell all the sensors to update (send) their values.
*
* Actuators are handled through callbacks on their value changing from the
* SmartDashboard widgets.
*/
void LiveWindow::UpdateValues() {
std::lock_guard<wpi::mutex> lock(m_impl->mutex);
// Only do this if either LiveWindow mode or telemetry is enabled.
@@ -348,3 +228,5 @@ void LiveWindow::UpdateValues() {
m_impl->startLiveWindow = false;
}
LiveWindow::LiveWindow() : m_impl(new Impl) {}

View File

@@ -20,18 +20,6 @@ using namespace frc;
std::set<MotorSafetyHelper*> MotorSafetyHelper::m_helperList;
wpi::mutex MotorSafetyHelper::m_listMutex;
/**
* The constructor for a MotorSafetyHelper object.
*
* The helper object is constructed for every object that wants to implement the
* Motor Safety protocol. The helper object has the code to actually do the
* timing and call the motors Stop() method when the timeout expires. The motor
* object is expected to call the Feed() method whenever the motors value is
* updated.
*
* @param safeObject a pointer to the motor object implementing MotorSafety.
* This is used to call the Stop() method on the motor.
*/
MotorSafetyHelper::MotorSafetyHelper(MotorSafety* safeObject)
: m_safeObject(safeObject) {
m_enabled = false;
@@ -47,54 +35,26 @@ MotorSafetyHelper::~MotorSafetyHelper() {
m_helperList.erase(this);
}
/**
* Feed the motor safety object.
*
* Resets the timer on this object that is used to do the timeouts.
*/
void MotorSafetyHelper::Feed() {
std::lock_guard<wpi::mutex> lock(m_thisMutex);
m_stopTime = Timer::GetFPGATimestamp() + m_expiration;
}
/**
* Set the expiration time for the corresponding motor safety object.
*
* @param expirationTime The timeout value in seconds.
*/
void MotorSafetyHelper::SetExpiration(double expirationTime) {
std::lock_guard<wpi::mutex> lock(m_thisMutex);
m_expiration = expirationTime;
}
/**
* Retrieve the timeout value for the corresponding motor safety object.
*
* @return the timeout value in seconds.
*/
double MotorSafetyHelper::GetExpiration() const {
std::lock_guard<wpi::mutex> lock(m_thisMutex);
return m_expiration;
}
/**
* Determine if the motor is still operating or has timed out.
*
* @return a true value if the motor is still operating normally and hasn't
* timed out.
*/
bool MotorSafetyHelper::IsAlive() const {
std::lock_guard<wpi::mutex> lock(m_thisMutex);
return !m_enabled || m_stopTime > Timer::GetFPGATimestamp();
}
/**
* Check if this motor has exceeded its timeout.
*
* This method is called periodically to determine if this motor has exceeded
* its timeout value. If it has, the stop method is called, and the motor is
* shut down until its value is updated again.
*/
void MotorSafetyHelper::Check() {
bool enabled;
double stopTime;
@@ -118,36 +78,16 @@ void MotorSafetyHelper::Check() {
}
}
/**
* Enable/disable motor safety for this device
*
* Turn on and off the motor safety option for this PWM object.
*
* @param enabled True if motor safety is enforced for this object
*/
void MotorSafetyHelper::SetSafetyEnabled(bool enabled) {
std::lock_guard<wpi::mutex> lock(m_thisMutex);
m_enabled = enabled;
}
/**
* Return the state of the motor safety enabled flag
*
* Return if the motor safety is currently enabled for this devicce.
*
* @return True if motor safety is enforced for this device
*/
bool MotorSafetyHelper::IsSafetyEnabled() const {
std::lock_guard<wpi::mutex> lock(m_thisMutex);
return m_enabled;
}
/**
* Check the motors to see if any have timed out.
*
* This static method is called periodically to poll all the motors and stop any
* that have timed out.
*/
void MotorSafetyHelper::CheckMotors() {
std::lock_guard<wpi::mutex> lock(m_listMutex);
for (auto elem : m_helperList) {

View File

@@ -13,14 +13,6 @@
using namespace frc;
/**
* Constructor.
*
* @param pwmChannel The PWM channel that the Nidec Brushless controller is
* attached to. 0-9 are on-board, 10-19 are on the MXP port.
* @param dioChannel The DIO channel that the Nidec Brushless controller is
* attached to. 0-9 are on-board, 10-25 are on the MXP port.
*/
NidecBrushless::NidecBrushless(int pwmChannel, int dioChannel)
: m_safetyHelper(this), m_dio(dioChannel), m_pwm(pwmChannel) {
AddChild(&m_dio);
@@ -36,14 +28,6 @@ NidecBrushless::NidecBrushless(int pwmChannel, int dioChannel)
SetName("Nidec Brushless", pwmChannel);
}
/**
* Set the PWM value.
*
* The PWM value is set using a range of -1.0 to 1.0, appropriately scaling the
* value for the FPGA.
*
* @param speed The speed value between -1.0 and 1.0 to set.
*/
void NidecBrushless::Set(double speed) {
if (!m_disabled) {
m_speed = speed;
@@ -53,98 +37,49 @@ void NidecBrushless::Set(double speed) {
m_safetyHelper.Feed();
}
/**
* Get the recently set value of the PWM.
*
* @return The most recently set value for the PWM between -1.0 and 1.0.
*/
double NidecBrushless::Get() const { return m_speed; }
void NidecBrushless::SetInverted(bool isInverted) { m_isInverted = isInverted; }
bool NidecBrushless::GetInverted() const { return m_isInverted; }
/**
* Write out the PID value as seen in the PIDOutput base object.
*
* @param output Write out the PWM value as was found in the PIDController
*/
void NidecBrushless::PIDWrite(double output) { Set(output); }
/**
* Set the safety expiration time.
*
* @param timeout The timeout (in seconds) for this motor object
*/
void NidecBrushless::SetExpiration(double timeout) {
m_safetyHelper.SetExpiration(timeout);
}
/**
* Return the safety expiration time.
*
* @return The expiration time value.
*/
double NidecBrushless::GetExpiration() const {
return m_safetyHelper.GetExpiration();
}
/**
* Check if the motor is currently alive or stopped due to a timeout.
*
* @return a bool value that is true if the motor has NOT timed out and should
* still be running.
*/
bool NidecBrushless::IsAlive() const { return m_safetyHelper.IsAlive(); }
/**
* Stop the motor. This is called by the MotorSafetyHelper object when it has a
* timeout for this PWM and needs to stop it from running. Calling Set() will
* re-enable the motor.
*/
void NidecBrushless::StopMotor() {
m_dio.UpdateDutyCycle(0.5);
m_pwm.SetDisabled();
}
/**
* Check if motor safety is enabled.
*
* @return True if motor safety is enforced for this object
*/
bool NidecBrushless::IsSafetyEnabled() const {
return m_safetyHelper.IsSafetyEnabled();
}
void NidecBrushless::SetSafetyEnabled(bool enabled) {
m_safetyHelper.SetSafetyEnabled(enabled);
}
void NidecBrushless::GetDescription(wpi::raw_ostream& desc) const {
desc << "Nidec " << GetChannel();
}
/**
* Disable the motor. The Enable() function must be called to re-enable
* the motor.
*/
void NidecBrushless::Disable() {
m_disabled = true;
m_dio.UpdateDutyCycle(0.5);
m_pwm.SetDisabled();
}
/**
* Re-enable the motor after Disable() has been called. The Set()
* function must be called to set a new motor speed.
*/
void NidecBrushless::StopMotor() {
m_dio.UpdateDutyCycle(0.5);
m_pwm.SetDisabled();
}
void NidecBrushless::Enable() { m_disabled = false; }
/**
* Gets the channel number associated with the object.
*
* @return The channel number.
*/
void NidecBrushless::PIDWrite(double output) { Set(output); }
void NidecBrushless::SetExpiration(double timeout) {
m_safetyHelper.SetExpiration(timeout);
}
double NidecBrushless::GetExpiration() const {
return m_safetyHelper.GetExpiration();
}
bool NidecBrushless::IsAlive() const { return m_safetyHelper.IsAlive(); }
void NidecBrushless::SetSafetyEnabled(bool enabled) {
m_safetyHelper.SetSafetyEnabled(enabled);
}
bool NidecBrushless::IsSafetyEnabled() const {
return m_safetyHelper.IsSafetyEnabled();
}
void NidecBrushless::GetDescription(wpi::raw_ostream& desc) const {
desc << "Nidec " << GetChannel();
}
int NidecBrushless::GetChannel() const { return m_pwm.GetChannel(); }
void NidecBrushless::InitSendable(SendableBuilder& builder) {

View File

@@ -15,12 +15,6 @@
using namespace frc;
/**
* Create a Notifier for timer event notification.
*
* @param handler The handler is called at the notification time which is set
* using StartSingle or StartPeriodic.
*/
Notifier::Notifier(TimerEventHandler handler) {
if (handler == nullptr)
wpi_setWPIErrorWithContext(NullParameter, "handler must not be nullptr");
@@ -53,9 +47,6 @@ Notifier::Notifier(TimerEventHandler handler) {
});
}
/**
* Free the resources for a timer event.
*/
Notifier::~Notifier() {
int32_t status = 0;
// atomically set handle to 0, then clean
@@ -69,9 +60,33 @@ Notifier::~Notifier() {
HAL_CleanNotifier(handle, &status);
}
/**
* Update the HAL alarm time.
*/
void Notifier::SetHandler(TimerEventHandler handler) {
std::lock_guard<wpi::mutex> lock(m_processMutex);
m_handler = handler;
}
void Notifier::StartSingle(double delay) {
std::lock_guard<wpi::mutex> lock(m_processMutex);
m_periodic = false;
m_period = delay;
m_expirationTime = Timer::GetFPGATimestamp() + m_period;
UpdateAlarm();
}
void Notifier::StartPeriodic(double period) {
std::lock_guard<wpi::mutex> lock(m_processMutex);
m_periodic = true;
m_period = period;
m_expirationTime = Timer::GetFPGATimestamp() + m_period;
UpdateAlarm();
}
void Notifier::Stop() {
int32_t status = 0;
HAL_CancelNotifierAlarm(m_notifier, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
void Notifier::UpdateAlarm() {
int32_t status = 0;
// Return if we are being destructed, or were not created successfully
@@ -81,61 +96,3 @@ void Notifier::UpdateAlarm() {
notifier, static_cast<uint64_t>(m_expirationTime * 1e6), &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Change the handler function.
*
* @param handler Handler
*/
void Notifier::SetHandler(TimerEventHandler handler) {
std::lock_guard<wpi::mutex> lock(m_processMutex);
m_handler = handler;
}
/**
* Register for single event notification.
*
* A timer event is queued for a single event after the specified delay.
*
* @param delay Seconds to wait before the handler is called.
*/
void Notifier::StartSingle(double delay) {
std::lock_guard<wpi::mutex> lock(m_processMutex);
m_periodic = false;
m_period = delay;
m_expirationTime = Timer::GetFPGATimestamp() + m_period;
UpdateAlarm();
}
/**
* Register for periodic event notification.
*
* A timer event is queued for periodic event notification. Each time the
* interrupt occurs, the event will be immediately requeued for the same time
* interval.
*
* @param period Period in seconds to call the handler starting one period
* after the call to this method.
*/
void Notifier::StartPeriodic(double period) {
std::lock_guard<wpi::mutex> lock(m_processMutex);
m_periodic = true;
m_period = period;
m_expirationTime = Timer::GetFPGATimestamp() + m_period;
UpdateAlarm();
}
/**
* Stop timer events from occuring.
*
* Stop any repeating timer events from occuring. This will also remove any
* single notification events from the queue.
*
* If a timer-based call to the registered handler is in progress, this function
* will block until the handler call is complete.
*/
void Notifier::Stop() {
int32_t status = 0;
HAL_CancelNotifierAlarm(m_notifier, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}

View File

@@ -22,28 +22,10 @@ constexpr const T& clamp(const T& value, const T& low, const T& high) {
return std::max(low, std::min(value, high));
}
/**
* Allocate a PID object with the given constants for P, I, D.
*
* @param Kp the proportional coefficient
* @param Ki the integral coefficient
* @param Kd the derivative coefficient
* @param source The PIDSource object that is used to get values
* @param output The PIDOutput object that is set to the output value
*/
PIDBase::PIDBase(double Kp, double Ki, double Kd, PIDSource& source,
PIDOutput& output)
: PIDBase(Kp, Ki, Kd, 0.0, source, output) {}
/**
* Allocate a PID object with the given constants for P, I, D.
*
* @param Kp the proportional coefficient
* @param Ki the integral coefficient
* @param Kd the derivative coefficient
* @param source The PIDSource object that is used to get values
* @param output The PIDOutput object that is set to the output value
*/
PIDBase::PIDBase(double Kp, double Ki, double Kd, double Kf, PIDSource& source,
PIDOutput& output)
: SendableBase(false) {
@@ -69,10 +51,203 @@ PIDBase::PIDBase(double Kp, double Ki, double Kd, double Kf, PIDSource& source,
SetName("PIDController", instances);
}
/**
* Read the input, calculate the output accordingly, and write to the output.
* This should only be called by the Notifier.
*/
double PIDBase::Get() const {
std::lock_guard<wpi::mutex> lock(m_thisMutex);
return m_result;
}
void PIDBase::SetContinuous(bool continuous) {
std::lock_guard<wpi::mutex> lock(m_thisMutex);
m_continuous = continuous;
}
void PIDBase::SetInputRange(double minimumInput, double maximumInput) {
{
std::lock_guard<wpi::mutex> lock(m_thisMutex);
m_minimumInput = minimumInput;
m_maximumInput = maximumInput;
m_inputRange = maximumInput - minimumInput;
}
SetSetpoint(m_setpoint);
}
void PIDBase::SetOutputRange(double minimumOutput, double maximumOutput) {
std::lock_guard<wpi::mutex> lock(m_thisMutex);
m_minimumOutput = minimumOutput;
m_maximumOutput = maximumOutput;
}
void PIDBase::SetPID(double p, double i, double d) {
{
std::lock_guard<wpi::mutex> lock(m_thisMutex);
m_P = p;
m_I = i;
m_D = d;
}
}
void PIDBase::SetPID(double p, double i, double d, double f) {
std::lock_guard<wpi::mutex> lock(m_thisMutex);
m_P = p;
m_I = i;
m_D = d;
m_F = f;
}
void PIDBase::SetP(double p) {
std::lock_guard<wpi::mutex> lock(m_thisMutex);
m_P = p;
}
void PIDBase::SetI(double i) {
std::lock_guard<wpi::mutex> lock(m_thisMutex);
m_I = i;
}
void PIDBase::SetD(double d) {
std::lock_guard<wpi::mutex> lock(m_thisMutex);
m_D = d;
}
void PIDBase::SetF(double f) {
std::lock_guard<wpi::mutex> lock(m_thisMutex);
m_F = f;
}
double PIDBase::GetP() const {
std::lock_guard<wpi::mutex> lock(m_thisMutex);
return m_P;
}
double PIDBase::GetI() const {
std::lock_guard<wpi::mutex> lock(m_thisMutex);
return m_I;
}
double PIDBase::GetD() const {
std::lock_guard<wpi::mutex> lock(m_thisMutex);
return m_D;
}
double PIDBase::GetF() const {
std::lock_guard<wpi::mutex> lock(m_thisMutex);
return m_F;
}
void PIDBase::SetSetpoint(double setpoint) {
{
std::lock_guard<wpi::mutex> lock(m_thisMutex);
if (m_maximumInput > m_minimumInput) {
if (setpoint > m_maximumInput)
m_setpoint = m_maximumInput;
else if (setpoint < m_minimumInput)
m_setpoint = m_minimumInput;
else
m_setpoint = setpoint;
} else {
m_setpoint = setpoint;
}
}
}
double PIDBase::GetSetpoint() const {
std::lock_guard<wpi::mutex> lock(m_thisMutex);
return m_setpoint;
}
double PIDBase::GetDeltaSetpoint() const {
std::lock_guard<wpi::mutex> lock(m_thisMutex);
return (m_setpoint - m_prevSetpoint) / m_setpointTimer.Get();
}
double PIDBase::GetError() const {
double setpoint = GetSetpoint();
{
std::lock_guard<wpi::mutex> lock(m_thisMutex);
return GetContinuousError(setpoint - m_pidInput->PIDGet());
}
}
double PIDBase::GetAvgError() const { return GetError(); }
void PIDBase::SetPIDSourceType(PIDSourceType pidSource) {
m_pidInput->SetPIDSourceType(pidSource);
}
PIDSourceType PIDBase::GetPIDSourceType() const {
return m_pidInput->GetPIDSourceType();
}
void PIDBase::SetTolerance(double percent) {
std::lock_guard<wpi::mutex> lock(m_thisMutex);
m_toleranceType = kPercentTolerance;
m_tolerance = percent;
}
void PIDBase::SetAbsoluteTolerance(double absTolerance) {
std::lock_guard<wpi::mutex> lock(m_thisMutex);
m_toleranceType = kAbsoluteTolerance;
m_tolerance = absTolerance;
}
void PIDBase::SetPercentTolerance(double percent) {
std::lock_guard<wpi::mutex> lock(m_thisMutex);
m_toleranceType = kPercentTolerance;
m_tolerance = percent;
}
void PIDBase::SetToleranceBuffer(int bufLength) {
std::lock_guard<wpi::mutex> lock(m_thisMutex);
// Create LinearDigitalFilter with original source as its source argument
m_filter = LinearDigitalFilter::MovingAverage(m_origSource, bufLength);
m_pidInput = &m_filter;
}
bool PIDBase::OnTarget() const {
double error = GetError();
std::lock_guard<wpi::mutex> lock(m_thisMutex);
switch (m_toleranceType) {
case kPercentTolerance:
return std::fabs(error) < m_tolerance / 100 * m_inputRange;
break;
case kAbsoluteTolerance:
return std::fabs(error) < m_tolerance;
break;
case kNoTolerance:
// TODO: this case needs an error
return false;
}
return false;
}
void PIDBase::Reset() {
std::lock_guard<wpi::mutex> lock(m_thisMutex);
m_prevError = 0;
m_totalError = 0;
m_result = 0;
}
void PIDBase::PIDWrite(double output) { SetSetpoint(output); }
void PIDBase::InitSendable(SendableBuilder& builder) {
builder.SetSmartDashboardType("PIDBase");
builder.SetSafeState([=]() { Reset(); });
builder.AddDoubleProperty("p", [=]() { return GetP(); },
[=](double value) { SetP(value); });
builder.AddDoubleProperty("i", [=]() { return GetI(); },
[=](double value) { SetI(value); });
builder.AddDoubleProperty("d", [=]() { return GetD(); },
[=](double value) { SetD(value); });
builder.AddDoubleProperty("f", [=]() { return GetF(); },
[=](double value) { SetF(value); });
builder.AddDoubleProperty("setpoint", [=]() { return GetSetpoint(); },
[=](double value) { SetSetpoint(value); });
}
void PIDBase::Calculate() {
if (m_origSource == nullptr || m_pidOutput == nullptr) return;
@@ -158,21 +333,6 @@ void PIDBase::Calculate() {
}
}
/**
* Calculate the feed forward term.
*
* Both of the provided feed forward calculations are velocity feed forwards.
* If a different feed forward calculation is desired, the user can override
* this function and provide his or her own. This function does no
* synchronization because the PIDBase class only calls it in synchronized
* code, so be careful if calling it oneself.
*
* If a velocity PID controller is being used, the F term should be set to 1
* over the maximum setpoint for the output. If a position PID controller is
* being used, the F term should be set to 1 over the maximum speed for the
* output measured in setpoint units per this controller's update period (see
* the default period in this class's constructor).
*/
double PIDBase::CalculateFeedForward() {
if (m_pidInput->GetPIDSourceType() == PIDSourceType::kRate) {
return m_F * GetSetpoint();
@@ -184,384 +344,6 @@ double PIDBase::CalculateFeedForward() {
}
}
/**
* Set the PID Controller gain parameters.
*
* Set the proportional, integral, and differential coefficients.
*
* @param p Proportional coefficient
* @param i Integral coefficient
* @param d Differential coefficient
*/
void PIDBase::SetPID(double p, double i, double d) {
{
std::lock_guard<wpi::mutex> lock(m_thisMutex);
m_P = p;
m_I = i;
m_D = d;
}
}
/**
* Set the PID Controller gain parameters.
*
* Set the proportional, integral, and differential coefficients.
*
* @param p Proportional coefficient
* @param i Integral coefficient
* @param d Differential coefficient
* @param f Feed forward coefficient
*/
void PIDBase::SetPID(double p, double i, double d, double f) {
std::lock_guard<wpi::mutex> lock(m_thisMutex);
m_P = p;
m_I = i;
m_D = d;
m_F = f;
}
/**
* Set the Proportional coefficient of the PID controller gain.
*
* @param p proportional coefficient
*/
void PIDBase::SetP(double p) {
std::lock_guard<wpi::mutex> lock(m_thisMutex);
m_P = p;
}
/**
* Set the Integral coefficient of the PID controller gain.
*
* @param i integral coefficient
*/
void PIDBase::SetI(double i) {
std::lock_guard<wpi::mutex> lock(m_thisMutex);
m_I = i;
}
/**
* Set the Differential coefficient of the PID controller gain.
*
* @param d differential coefficient
*/
void PIDBase::SetD(double d) {
std::lock_guard<wpi::mutex> lock(m_thisMutex);
m_D = d;
}
/**
* Get the Feed forward coefficient of the PID controller gain.
*
* @param f Feed forward coefficient
*/
void PIDBase::SetF(double f) {
std::lock_guard<wpi::mutex> lock(m_thisMutex);
m_F = f;
}
/**
* Get the Proportional coefficient.
*
* @return proportional coefficient
*/
double PIDBase::GetP() const {
std::lock_guard<wpi::mutex> lock(m_thisMutex);
return m_P;
}
/**
* Get the Integral coefficient.
*
* @return integral coefficient
*/
double PIDBase::GetI() const {
std::lock_guard<wpi::mutex> lock(m_thisMutex);
return m_I;
}
/**
* Get the Differential coefficient.
*
* @return differential coefficient
*/
double PIDBase::GetD() const {
std::lock_guard<wpi::mutex> lock(m_thisMutex);
return m_D;
}
/**
* Get the Feed forward coefficient.
*
* @return Feed forward coefficient
*/
double PIDBase::GetF() const {
std::lock_guard<wpi::mutex> lock(m_thisMutex);
return m_F;
}
/**
* Return the current PID result.
*
* This is always centered on zero and constrained the the max and min outs.
*
* @return the latest calculated output
*/
double PIDBase::Get() const {
std::lock_guard<wpi::mutex> lock(m_thisMutex);
return m_result;
}
/**
* Set the PID controller to consider the input to be continuous,
*
* Rather then using the max and min input range as constraints, it considers
* them to be the same point and automatically calculates the shortest route to
* the setpoint.
*
* @param continuous true turns on continuous, false turns off continuous
*/
void PIDBase::SetContinuous(bool continuous) {
std::lock_guard<wpi::mutex> lock(m_thisMutex);
m_continuous = continuous;
}
/**
* Sets the maximum and minimum values expected from the input.
*
* @param minimumInput the minimum value expected from the input
* @param maximumInput the maximum value expected from the output
*/
void PIDBase::SetInputRange(double minimumInput, double maximumInput) {
{
std::lock_guard<wpi::mutex> lock(m_thisMutex);
m_minimumInput = minimumInput;
m_maximumInput = maximumInput;
m_inputRange = maximumInput - minimumInput;
}
SetSetpoint(m_setpoint);
}
/**
* Sets the minimum and maximum values to write.
*
* @param minimumOutput the minimum value to write to the output
* @param maximumOutput the maximum value to write to the output
*/
void PIDBase::SetOutputRange(double minimumOutput, double maximumOutput) {
std::lock_guard<wpi::mutex> lock(m_thisMutex);
m_minimumOutput = minimumOutput;
m_maximumOutput = maximumOutput;
}
/**
* Set the setpoint for the PIDBase.
*
* @param setpoint the desired setpoint
*/
void PIDBase::SetSetpoint(double setpoint) {
{
std::lock_guard<wpi::mutex> lock(m_thisMutex);
if (m_maximumInput > m_minimumInput) {
if (setpoint > m_maximumInput)
m_setpoint = m_maximumInput;
else if (setpoint < m_minimumInput)
m_setpoint = m_minimumInput;
else
m_setpoint = setpoint;
} else {
m_setpoint = setpoint;
}
}
}
/**
* Returns the current setpoint of the PIDBase.
*
* @return the current setpoint
*/
double PIDBase::GetSetpoint() const {
std::lock_guard<wpi::mutex> lock(m_thisMutex);
return m_setpoint;
}
/**
* Returns the change in setpoint over time of the PIDBase.
*
* @return the change in setpoint over time
*/
double PIDBase::GetDeltaSetpoint() const {
std::lock_guard<wpi::mutex> lock(m_thisMutex);
return (m_setpoint - m_prevSetpoint) / m_setpointTimer.Get();
}
/**
* Returns the current difference of the input from the setpoint.
*
* @return the current error
*/
double PIDBase::GetError() const {
double setpoint = GetSetpoint();
{
std::lock_guard<wpi::mutex> lock(m_thisMutex);
return GetContinuousError(setpoint - m_pidInput->PIDGet());
}
}
/**
* Returns the current average of the error over the past few iterations.
*
* You can specify the number of iterations to average with SetToleranceBuffer()
* (defaults to 1). This is the same value that is used for OnTarget().
*
* @return the average error
*/
double PIDBase::GetAvgError() const { return GetError(); }
/**
* Sets what type of input the PID controller will use.
*/
void PIDBase::SetPIDSourceType(PIDSourceType pidSource) {
m_pidInput->SetPIDSourceType(pidSource);
}
/**
* Returns the type of input the PID controller is using.
*
* @return the PID controller input type
*/
PIDSourceType PIDBase::GetPIDSourceType() const {
return m_pidInput->GetPIDSourceType();
}
/*
* Set the percentage error which is considered tolerable for use with
* OnTarget.
*
* @param percentage error which is tolerable
*/
void PIDBase::SetTolerance(double percent) {
std::lock_guard<wpi::mutex> lock(m_thisMutex);
m_toleranceType = kPercentTolerance;
m_tolerance = percent;
}
/*
* Set the absolute error which is considered tolerable for use with
* OnTarget.
*
* @param percentage error which is tolerable
*/
void PIDBase::SetAbsoluteTolerance(double absTolerance) {
std::lock_guard<wpi::mutex> lock(m_thisMutex);
m_toleranceType = kAbsoluteTolerance;
m_tolerance = absTolerance;
}
/*
* Set the percentage error which is considered tolerable for use with
* OnTarget.
*
* @param percentage error which is tolerable
*/
void PIDBase::SetPercentTolerance(double percent) {
std::lock_guard<wpi::mutex> lock(m_thisMutex);
m_toleranceType = kPercentTolerance;
m_tolerance = percent;
}
/*
* Set the number of previous error samples to average for tolerancing. When
* determining whether a mechanism is on target, the user may want to use a
* rolling average of previous measurements instead of a precise position or
* velocity. This is useful for noisy sensors which return a few erroneous
* measurements when the mechanism is on target. However, the mechanism will
* not register as on target for at least the specified bufLength cycles.
*
* @param bufLength Number of previous cycles to average. Defaults to 1.
*/
void PIDBase::SetToleranceBuffer(int bufLength) {
std::lock_guard<wpi::mutex> lock(m_thisMutex);
// Create LinearDigitalFilter with original source as its source argument
m_filter = LinearDigitalFilter::MovingAverage(m_origSource, bufLength);
m_pidInput = &m_filter;
}
/*
* Return true if the error is within the percentage of the total input range,
* determined by SetTolerance. This asssumes that the maximum and minimum input
* were set using SetInput.
*
* Currently this just reports on target as the actual value passes through the
* setpoint. Ideally it should be based on being within the tolerance for some
* period of time.
*
* This will return false until at least one input value has been computed.
*/
bool PIDBase::OnTarget() const {
double error = GetError();
std::lock_guard<wpi::mutex> lock(m_thisMutex);
switch (m_toleranceType) {
case kPercentTolerance:
return std::fabs(error) < m_tolerance / 100 * m_inputRange;
break;
case kAbsoluteTolerance:
return std::fabs(error) < m_tolerance;
break;
case kNoTolerance:
// TODO: this case needs an error
return false;
}
return false;
}
/**
* Reset the previous error, the integral term, and disable the controller.
*/
void PIDBase::Reset() {
std::lock_guard<wpi::mutex> lock(m_thisMutex);
m_prevError = 0;
m_totalError = 0;
m_result = 0;
}
/**
* Passes the output directly to SetSetpoint().
*
* PIDControllers can be nested by passing a PIDController as another
* PIDController's output. In that case, the output of the parent controller
* becomes the input (i.e., the reference) of the child.
*
* It is the caller's responsibility to put the data into a valid form for
* SetSetpoint().
*/
void PIDBase::PIDWrite(double output) { SetSetpoint(output); }
void PIDBase::InitSendable(SendableBuilder& builder) {
builder.SetSmartDashboardType("PIDBase");
builder.SetSafeState([=]() { Reset(); });
builder.AddDoubleProperty("p", [=]() { return GetP(); },
[=](double value) { SetP(value); });
builder.AddDoubleProperty("i", [=]() { return GetI(); },
[=](double value) { SetI(value); });
builder.AddDoubleProperty("d", [=]() { return GetD(); },
[=](double value) { SetD(value); });
builder.AddDoubleProperty("f", [=]() { return GetF(); },
[=](double value) { SetF(value); });
builder.AddDoubleProperty("setpoint", [=]() { return GetSetpoint(); },
[=](double value) { SetSetpoint(value); });
}
/**
* Wraps error around for continuous inputs. The original error is returned if
* continuous mode is disabled. This is an unsynchronized function.
*
* @param error The current error of the PID controller.
* @return Error for continuous inputs.
*/
double PIDBase::GetContinuousError(double error) const {
if (m_continuous && m_inputRange != 0) {
error = std::fmod(error, m_inputRange);

View File

@@ -13,67 +13,19 @@
using namespace frc;
/**
* Allocate a PID object with the given constants for P, I, D.
*
* @param Kp the proportional coefficient
* @param Ki the integral coefficient
* @param Kd the derivative coefficient
* @param source The PIDSource object that is used to get values
* @param output The PIDOutput object that is set to the output value
* @param period the loop time for doing calculations. This particularly
* effects calculations of the integral and differental terms.
* The default is 50ms.
*/
PIDController::PIDController(double Kp, double Ki, double Kd, PIDSource* source,
PIDOutput* output, double period)
: PIDController(Kp, Ki, Kd, 0.0, *source, *output, period) {}
/**
* Allocate a PID object with the given constants for P, I, D.
*
* @param Kp the proportional coefficient
* @param Ki the integral coefficient
* @param Kd the derivative coefficient
* @param source The PIDSource object that is used to get values
* @param output The PIDOutput object that is set to the output value
* @param period the loop time for doing calculations. This particularly
* effects calculations of the integral and differental terms.
* The default is 50ms.
*/
PIDController::PIDController(double Kp, double Ki, double Kd, double Kf,
PIDSource* source, PIDOutput* output,
double period)
: PIDController(Kp, Ki, Kd, Kf, *source, *output, period) {}
/**
* Allocate a PID object with the given constants for P, I, D.
*
* @param Kp the proportional coefficient
* @param Ki the integral coefficient
* @param Kd the derivative coefficient
* @param source The PIDSource object that is used to get values
* @param output The PIDOutput object that is set to the output value
* @param period the loop time for doing calculations. This particularly
* effects calculations of the integral and differental terms.
* The default is 50ms.
*/
PIDController::PIDController(double Kp, double Ki, double Kd, PIDSource& source,
PIDOutput& output, double period)
: PIDController(Kp, Ki, Kd, 0.0, source, output, period) {}
/**
* Allocate a PID object with the given constants for P, I, D.
*
* @param Kp the proportional coefficient
* @param Ki the integral coefficient
* @param Kd the derivative coefficient
* @param source The PIDSource object that is used to get values
* @param output The PIDOutput object that is set to the output value
* @param period the loop time for doing calculations. This particularly
* effects calculations of the integral and differental terms.
* The default is 50ms.
*/
PIDController::PIDController(double Kp, double Ki, double Kd, double Kf,
PIDSource& source, PIDOutput& output,
double period)
@@ -87,9 +39,6 @@ PIDController::~PIDController() {
m_controlLoop->Stop();
}
/**
* Begin running the PIDController.
*/
void PIDController::Enable() {
{
std::lock_guard<wpi::mutex> lock(m_thisMutex);
@@ -97,9 +46,6 @@ void PIDController::Enable() {
}
}
/**
* Stop running the PIDController, this sets the output to zero before stopping.
*/
void PIDController::Disable() {
{
// Ensures m_enabled modification and PIDWrite() call occur atomically
@@ -113,9 +59,6 @@ void PIDController::Disable() {
}
}
/**
* Set the enabled state of the PIDController.
*/
void PIDController::SetEnabled(bool enable) {
if (enable) {
Enable();
@@ -124,17 +67,11 @@ void PIDController::SetEnabled(bool enable) {
}
}
/**
* Return true if PIDController is enabled.
*/
bool PIDController::IsEnabled() const {
std::lock_guard<wpi::mutex> lock(m_thisMutex);
return m_enabled;
}
/**
* Reset the previous error, the integral term, and disable the controller.
*/
void PIDController::Reset() {
Disable();

View File

@@ -9,11 +9,6 @@
using namespace frc;
/**
* Set which parameter you are using as a process control variable.
*
* @param pidSource An enum to select the parameter.
*/
void PIDSource::SetPIDSourceType(PIDSourceType pidSource) {
m_pidSource = pidSource;
}

View File

@@ -18,16 +18,6 @@
using namespace frc;
/**
* Allocate a PWM given a channel number.
*
* Checks channel value range and allocates the appropriate channel.
* The allocation is only done to help users ensure that they don't double
* assign channels.
*
* @param channel The PWM channel number. 0-9 are on-board, 10-19 are on the
* MXP port
*/
PWM::PWM(int channel) {
if (!SensorUtil::CheckPWMChannel(channel)) {
wpi_setWPIErrorWithContext(ChannelIndexOutOfRange,
@@ -57,11 +47,6 @@ PWM::PWM(int channel) {
SetName("PWM", channel);
}
/**
* Free the PWM channel.
*
* Free the resource associated with the PWM channel and set the value to 0.
*/
PWM::~PWM() {
int32_t status = 0;
@@ -72,168 +57,6 @@ PWM::~PWM() {
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Optionally eliminate the deadband from a speed controller.
*
* @param eliminateDeadband If true, set the motor curve on the Jaguar to
* eliminate the deadband in the middle of the range.
* Otherwise, keep the full range without modifying
* any values.
*/
void PWM::EnableDeadbandElimination(bool eliminateDeadband) {
if (StatusIsFatal()) return;
int32_t status = 0;
HAL_SetPWMEliminateDeadband(m_handle, eliminateDeadband, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Set the bounds on the PWM pulse widths.
*
* This sets the bounds on the PWM values for a particular type of controller.
* The values determine the upper and lower speeds as well as the deadband
* bracket.
*
* @param max The max PWM pulse width in ms
* @param deadbandMax The high end of the deadband range pulse width in ms
* @param center The center (off) pulse width in ms
* @param deadbandMin The low end of the deadband pulse width in ms
* @param min The minimum pulse width in ms
*/
void PWM::SetBounds(double max, double deadbandMax, double center,
double deadbandMin, double min) {
if (StatusIsFatal()) return;
int32_t status = 0;
HAL_SetPWMConfig(m_handle, max, deadbandMax, center, deadbandMin, min,
&status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Set the bounds on the PWM values.
*
* This sets the bounds on the PWM values for a particular each type of
* controller. The values determine the upper and lower speeds as well as the
* deadband bracket.
*
* @param max The Minimum pwm value
* @param deadbandMax The high end of the deadband range
* @param center The center speed (off)
* @param deadbandMin The low end of the deadband range
* @param min The minimum pwm value
*/
void PWM::SetRawBounds(int max, int deadbandMax, int center, int deadbandMin,
int min) {
if (StatusIsFatal()) return;
int32_t status = 0;
HAL_SetPWMConfigRaw(m_handle, max, deadbandMax, center, deadbandMin, min,
&status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Get the bounds on the PWM values.
*
* This Gets the bounds on the PWM values for a particular each type of
* controller. The values determine the upper and lower speeds as well as the
* deadband bracket.
*
* @param max The Minimum pwm value
* @param deadbandMax The high end of the deadband range
* @param center The center speed (off)
* @param deadbandMin The low end of the deadband range
* @param min The minimum pwm value
*/
void PWM::GetRawBounds(int* max, int* deadbandMax, int* center,
int* deadbandMin, int* min) {
int32_t status = 0;
HAL_GetPWMConfigRaw(m_handle, max, deadbandMax, center, deadbandMin, min,
&status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Set the PWM value based on a position.
*
* This is intended to be used by servos.
*
* @pre SetMaxPositivePwm() called.
* @pre SetMinNegativePwm() called.
*
* @param pos The position to set the servo between 0.0 and 1.0.
*/
void PWM::SetPosition(double pos) {
if (StatusIsFatal()) return;
int32_t status = 0;
HAL_SetPWMPosition(m_handle, pos, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Get the PWM value in terms of a position.
*
* This is intended to be used by servos.
*
* @pre SetMaxPositivePwm() called.
* @pre SetMinNegativePwm() called.
*
* @return The position the servo is set to between 0.0 and 1.0.
*/
double PWM::GetPosition() const {
if (StatusIsFatal()) return 0.0;
int32_t status = 0;
double position = HAL_GetPWMPosition(m_handle, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
return position;
}
/**
* Set the PWM value based on a speed.
*
* This is intended to be used by speed controllers.
*
* @pre SetMaxPositivePwm() called.
* @pre SetMinPositivePwm() called.
* @pre SetCenterPwm() called.
* @pre SetMaxNegativePwm() called.
* @pre SetMinNegativePwm() called.
*
* @param speed The speed to set the speed controller between -1.0 and 1.0.
*/
void PWM::SetSpeed(double speed) {
if (StatusIsFatal()) return;
int32_t status = 0;
HAL_SetPWMSpeed(m_handle, speed, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Get the PWM value in terms of speed.
*
* This is intended to be used by speed controllers.
*
* @pre SetMaxPositivePwm() called.
* @pre SetMinPositivePwm() called.
* @pre SetMaxNegativePwm() called.
* @pre SetMinNegativePwm() called.
*
* @return The most recently set speed between -1.0 and 1.0.
*/
double PWM::GetSpeed() const {
if (StatusIsFatal()) return 0.0;
int32_t status = 0;
double speed = HAL_GetPWMSpeed(m_handle, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
return speed;
}
/**
* Set the PWM value directly to the hardware.
*
* Write a raw value to a PWM channel.
*
* @param value Raw PWM value.
*/
void PWM::SetRaw(uint16_t value) {
if (StatusIsFatal()) return;
@@ -242,13 +65,6 @@ void PWM::SetRaw(uint16_t value) {
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Get the PWM value directly from the hardware.
*
* Read a raw value from a PWM channel.
*
* @return Raw PWM control value.
*/
uint16_t PWM::GetRaw() const {
if (StatusIsFatal()) return 0;
@@ -259,11 +75,45 @@ uint16_t PWM::GetRaw() const {
return value;
}
/**
* Slow down the PWM signal for old devices.
*
* @param mult The period multiplier to apply to this channel
*/
void PWM::SetPosition(double pos) {
if (StatusIsFatal()) return;
int32_t status = 0;
HAL_SetPWMPosition(m_handle, pos, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
double PWM::GetPosition() const {
if (StatusIsFatal()) return 0.0;
int32_t status = 0;
double position = HAL_GetPWMPosition(m_handle, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
return position;
}
void PWM::SetSpeed(double speed) {
if (StatusIsFatal()) return;
int32_t status = 0;
HAL_SetPWMSpeed(m_handle, speed, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
double PWM::GetSpeed() const {
if (StatusIsFatal()) return 0.0;
int32_t status = 0;
double speed = HAL_GetPWMSpeed(m_handle, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
return speed;
}
void PWM::SetDisabled() {
if (StatusIsFatal()) return;
int32_t status = 0;
HAL_SetPWMDisabled(m_handle, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
void PWM::SetPeriodMultiplier(PeriodMultiplier mult) {
if (StatusIsFatal()) return;
@@ -288,19 +138,6 @@ void PWM::SetPeriodMultiplier(PeriodMultiplier mult) {
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Temporarily disables the PWM output. The next set call will reenable
* the output.
*/
void PWM::SetDisabled() {
if (StatusIsFatal()) return;
int32_t status = 0;
HAL_SetPWMDisabled(m_handle, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
void PWM::SetZeroLatch() {
if (StatusIsFatal()) return;
@@ -310,6 +147,41 @@ void PWM::SetZeroLatch() {
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
void PWM::EnableDeadbandElimination(bool eliminateDeadband) {
if (StatusIsFatal()) return;
int32_t status = 0;
HAL_SetPWMEliminateDeadband(m_handle, eliminateDeadband, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
void PWM::SetBounds(double max, double deadbandMax, double center,
double deadbandMin, double min) {
if (StatusIsFatal()) return;
int32_t status = 0;
HAL_SetPWMConfig(m_handle, max, deadbandMax, center, deadbandMin, min,
&status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
void PWM::SetRawBounds(int max, int deadbandMax, int center, int deadbandMin,
int min) {
if (StatusIsFatal()) return;
int32_t status = 0;
HAL_SetPWMConfigRaw(m_handle, max, deadbandMax, center, deadbandMin, min,
&status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
void PWM::GetRawBounds(int* max, int* deadbandMax, int* center,
int* deadbandMin, int* min) {
int32_t status = 0;
HAL_GetPWMConfigRaw(m_handle, max, deadbandMax, center, deadbandMin, min,
&status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
int PWM::GetChannel() const { return m_channel; }
void PWM::InitSendable(SendableBuilder& builder) {
builder.SetSmartDashboardType("PWM");
builder.SetSafeState([=]() { SetDisabled(); });

View File

@@ -11,31 +11,10 @@
using namespace frc;
/**
* Constructor for a PWM Speed Controller connected via PWM.
*
* @param channel The PWM channel that the controller is attached to. 0-9 are
* on-board, 10-19 are on the MXP port
*/
PWMSpeedController::PWMSpeedController(int channel) : SafePWM(channel) {}
/**
* Set the PWM value.
*
* The PWM value is set using a range of -1.0 to 1.0, appropriately
* scaling the value for the FPGA.
*
* @param speed The speed value between -1.0 and 1.0 to set.
*/
void PWMSpeedController::Set(double speed) {
SetSpeed(m_isInverted ? -speed : speed);
}
/**
* Get the recently set value of the PWM.
*
* @return The most recently set value for the PWM between -1.0 and 1.0.
*/
double PWMSpeedController::Get() const { return GetSpeed(); }
void PWMSpeedController::SetInverted(bool isInverted) {
@@ -48,13 +27,10 @@ void PWMSpeedController::Disable() { SetDisabled(); }
void PWMSpeedController::StopMotor() { SafePWM::StopMotor(); }
/**
* Write out the PID value as seen in the PIDOutput base object.
*
* @param output Write out the PWM value as was found in the PIDController
*/
void PWMSpeedController::PIDWrite(double output) { Set(output); }
PWMSpeedController::PWMSpeedController(int channel) : SafePWM(channel) {}
void PWMSpeedController::InitSendable(SendableBuilder& builder) {
builder.SetSmartDashboardType("Speed Controller");
builder.SetSafeState([=]() { SetDisabled(); });

View File

@@ -11,12 +11,6 @@
using namespace frc;
/**
* Construct a PWMTalonSRX connected via PWM.
*
* @param channel The PWM channel that the PWMTalonSRX is attached to. 0-9 are
* on-board, 10-19 are on the MXP port
*/
PWMTalonSRX::PWMTalonSRX(int channel) : PWMSpeedController(channel) {
/* Note that the PWMTalonSRX uses the following bounds for PWM values. These
* values should work reasonably well for most controllers, but if users

View File

@@ -11,12 +11,6 @@
using namespace frc;
/**
* Construct a PWMVictorSPX connected via PWM.
*
* @param channel The PWM channel that the PWMVictorSPX is attached to. 0-9 are
* on-board, 10-19 are on the MXP port
*/
PWMVictorSPX::PWMVictorSPX(int channel) : PWMSpeedController(channel) {
/* Note that the PWMVictorSPX uses the following bounds for PWM values. These
* values should work reasonably well for most controllers, but if users

View File

@@ -21,9 +21,6 @@ using namespace frc;
PowerDistributionPanel::PowerDistributionPanel() : PowerDistributionPanel(0) {}
/**
* Initialize the PDP.
*/
PowerDistributionPanel::PowerDistributionPanel(int module) : m_module(module) {
int32_t status = 0;
HAL_InitializePDP(m_module, &status);
@@ -36,11 +33,6 @@ PowerDistributionPanel::PowerDistributionPanel(int module) : m_module(module) {
SetName("PowerDistributionPanel", module);
}
/**
* Query the input voltage of the PDP.
*
* @return The voltage of the PDP in volts
*/
double PowerDistributionPanel::GetVoltage() const {
int32_t status = 0;
@@ -53,11 +45,6 @@ double PowerDistributionPanel::GetVoltage() const {
return voltage;
}
/**
* Query the temperature of the PDP.
*
* @return The temperature of the PDP in degrees Celsius
*/
double PowerDistributionPanel::GetTemperature() const {
int32_t status = 0;
@@ -70,11 +57,6 @@ double PowerDistributionPanel::GetTemperature() const {
return temperature;
}
/**
* Query the current of a single channel of the PDP.
*
* @return The current of one of the PDP channels (channels 0-15) in Amperes
*/
double PowerDistributionPanel::GetCurrent(int channel) const {
int32_t status = 0;
@@ -94,11 +76,6 @@ double PowerDistributionPanel::GetCurrent(int channel) const {
return current;
}
/**
* Query the total current of all monitored PDP channels (0-15).
*
* @return The the total current drawn from the PDP channels in Amperes
*/
double PowerDistributionPanel::GetTotalCurrent() const {
int32_t status = 0;
@@ -111,11 +88,6 @@ double PowerDistributionPanel::GetTotalCurrent() const {
return current;
}
/**
* Query the total power drawn from the monitored PDP channels.
*
* @return The the total power drawn from the PDP channels in Watts
*/
double PowerDistributionPanel::GetTotalPower() const {
int32_t status = 0;
@@ -128,11 +100,6 @@ double PowerDistributionPanel::GetTotalPower() const {
return power;
}
/**
* Query the total energy drawn from the monitored PDP channels.
*
* @return The the total energy drawn from the PDP channels in Joules
*/
double PowerDistributionPanel::GetTotalEnergy() const {
int32_t status = 0;
@@ -145,11 +112,6 @@ double PowerDistributionPanel::GetTotalEnergy() const {
return energy;
}
/**
* Reset the total energy drawn from the PDP.
*
* @see PowerDistributionPanel#GetTotalEnergy
*/
void PowerDistributionPanel::ResetTotalEnergy() {
int32_t status = 0;
@@ -160,9 +122,6 @@ void PowerDistributionPanel::ResetTotalEnergy() {
}
}
/**
* Remove all of the fault flags on the PDP.
*/
void PowerDistributionPanel::ClearStickyFaults() {
int32_t status = 0;

View File

@@ -20,6 +20,88 @@ using namespace frc;
// The Preferences table name
static wpi::StringRef kTableName{"Preferences"};
Preferences* Preferences::GetInstance() {
static Preferences instance;
return &instance;
}
std::vector<std::string> Preferences::GetKeys() { return m_table->GetKeys(); }
std::string Preferences::GetString(wpi::StringRef key,
wpi::StringRef defaultValue) {
return m_table->GetString(key, defaultValue);
}
int Preferences::GetInt(wpi::StringRef key, int defaultValue) {
return static_cast<int>(m_table->GetNumber(key, defaultValue));
}
double Preferences::GetDouble(wpi::StringRef key, double defaultValue) {
return m_table->GetNumber(key, defaultValue);
}
float Preferences::GetFloat(wpi::StringRef key, float defaultValue) {
return m_table->GetNumber(key, defaultValue);
}
bool Preferences::GetBoolean(wpi::StringRef key, bool defaultValue) {
return m_table->GetBoolean(key, defaultValue);
}
int64_t Preferences::GetLong(wpi::StringRef key, int64_t defaultValue) {
return static_cast<int64_t>(m_table->GetNumber(key, defaultValue));
}
void Preferences::PutString(wpi::StringRef key, wpi::StringRef value) {
auto entry = m_table->GetEntry(key);
entry.SetString(value);
entry.SetPersistent();
}
void Preferences::PutInt(wpi::StringRef key, int value) {
auto entry = m_table->GetEntry(key);
entry.SetDouble(value);
entry.SetPersistent();
}
void Preferences::PutDouble(wpi::StringRef key, double value) {
auto entry = m_table->GetEntry(key);
entry.SetDouble(value);
entry.SetPersistent();
}
void Preferences::PutFloat(wpi::StringRef key, float value) {
auto entry = m_table->GetEntry(key);
entry.SetDouble(value);
entry.SetPersistent();
}
void Preferences::PutBoolean(wpi::StringRef key, bool value) {
auto entry = m_table->GetEntry(key);
entry.SetBoolean(value);
entry.SetPersistent();
}
void Preferences::PutLong(wpi::StringRef key, int64_t value) {
auto entry = m_table->GetEntry(key);
entry.SetDouble(value);
entry.SetPersistent();
}
bool Preferences::ContainsKey(wpi::StringRef key) {
return m_table->ContainsKey(key);
}
void Preferences::Remove(wpi::StringRef key) { m_table->Delete(key); }
void Preferences::RemoveAll() {
for (auto preference : GetKeys()) {
if (preference != ".type") {
Remove(preference);
}
}
}
Preferences::Preferences()
: m_table(nt::NetworkTableInstance::GetDefault().GetTable(kTableName)) {
m_table->GetEntry(".type").SetString("RobotPreferences");
@@ -30,206 +112,3 @@ Preferences::Preferences()
NT_NOTIFY_NEW | NT_NOTIFY_IMMEDIATE);
HAL_Report(HALUsageReporting::kResourceType_Preferences, 0);
}
/**
* Get the one and only {@link Preferences} object.
*
* @return pointer to the {@link Preferences}
*/
Preferences* Preferences::GetInstance() {
static Preferences instance;
return &instance;
}
/**
* Returns a vector of all the keys.
*
* @return a vector of the keys
*/
std::vector<std::string> Preferences::GetKeys() { return m_table->GetKeys(); }
/**
* Returns the string at the given key. If this table does not have a value
* for that position, then the given defaultValue will be returned.
*
* @param key the key
* @param defaultValue the value to return if none exists in the table
* @return either the value in the table, or the defaultValue
*/
std::string Preferences::GetString(wpi::StringRef key,
wpi::StringRef defaultValue) {
return m_table->GetString(key, defaultValue);
}
/**
* Returns the int at the given key. If this table does not have a value for
* that position, then the given defaultValue value will be returned.
*
* @param key the key
* @param defaultValue the value to return if none exists in the table
* @return either the value in the table, or the defaultValue
*/
int Preferences::GetInt(wpi::StringRef key, int defaultValue) {
return static_cast<int>(m_table->GetNumber(key, defaultValue));
}
/**
* Returns the double at the given key. If this table does not have a value
* for that position, then the given defaultValue value will be returned.
*
* @param key the key
* @param defaultValue the value to return if none exists in the table
* @return either the value in the table, or the defaultValue
*/
double Preferences::GetDouble(wpi::StringRef key, double defaultValue) {
return m_table->GetNumber(key, defaultValue);
}
/**
* Returns the float at the given key. If this table does not have a value
* for that position, then the given defaultValue value will be returned.
*
* @param key the key
* @param defaultValue the value to return if none exists in the table
* @return either the value in the table, or the defaultValue
*/
float Preferences::GetFloat(wpi::StringRef key, float defaultValue) {
return m_table->GetNumber(key, defaultValue);
}
/**
* Returns the boolean at the given key. If this table does not have a value
* for that position, then the given defaultValue value will be returned.
*
* @param key the key
* @param defaultValue the value to return if none exists in the table
* @return either the value in the table, or the defaultValue
*/
bool Preferences::GetBoolean(wpi::StringRef key, bool defaultValue) {
return m_table->GetBoolean(key, defaultValue);
}
/**
* Returns the long (int64_t) at the given key. If this table does not have a
* value for that position, then the given defaultValue value will be returned.
*
* @param key the key
* @param defaultValue the value to return if none exists in the table
* @return either the value in the table, or the defaultValue
*/
int64_t Preferences::GetLong(wpi::StringRef key, int64_t defaultValue) {
return static_cast<int64_t>(m_table->GetNumber(key, defaultValue));
}
/**
* Puts the given string into the preferences table.
*
* The value may not have quotation marks, nor may the key have any whitespace
* nor an equals sign.
*
* @param key the key
* @param value the value
*/
void Preferences::PutString(wpi::StringRef key, wpi::StringRef value) {
auto entry = m_table->GetEntry(key);
entry.SetString(value);
entry.SetPersistent();
}
/**
* Puts the given int into the preferences table.
*
* The key may not have any whitespace nor an equals sign.
*
* @param key the key
* @param value the value
*/
void Preferences::PutInt(wpi::StringRef key, int value) {
auto entry = m_table->GetEntry(key);
entry.SetDouble(value);
entry.SetPersistent();
}
/**
* Puts the given double into the preferences table.
*
* The key may not have any whitespace nor an equals sign.
*
* @param key the key
* @param value the value
*/
void Preferences::PutDouble(wpi::StringRef key, double value) {
auto entry = m_table->GetEntry(key);
entry.SetDouble(value);
entry.SetPersistent();
}
/**
* Puts the given float into the preferences table.
*
* The key may not have any whitespace nor an equals sign.
*
* @param key the key
* @param value the value
*/
void Preferences::PutFloat(wpi::StringRef key, float value) {
auto entry = m_table->GetEntry(key);
entry.SetDouble(value);
entry.SetPersistent();
}
/**
* Puts the given boolean into the preferences table.
*
* The key may not have any whitespace nor an equals sign.
*
* @param key the key
* @param value the value
*/
void Preferences::PutBoolean(wpi::StringRef key, bool value) {
auto entry = m_table->GetEntry(key);
entry.SetBoolean(value);
entry.SetPersistent();
}
/**
* Puts the given long (int64_t) into the preferences table.
*
* The key may not have any whitespace nor an equals sign.
*
* @param key the key
* @param value the value
*/
void Preferences::PutLong(wpi::StringRef key, int64_t value) {
auto entry = m_table->GetEntry(key);
entry.SetDouble(value);
entry.SetPersistent();
}
/**
* Returns whether or not there is a key with the given name.
*
* @param key the key
* @return if there is a value at the given key
*/
bool Preferences::ContainsKey(wpi::StringRef key) {
return m_table->ContainsKey(key);
}
/**
* Remove a preference.
*
* @param key the key
*/
void Preferences::Remove(wpi::StringRef key) { m_table->Delete(key); }
/**
* Remove all preferences.
*/
void Preferences::RemoveAll() {
for (auto preference : GetKeys()) {
if (preference != ".type") {
Remove(preference);
}
}
}

View File

@@ -19,15 +19,6 @@
using namespace frc;
/**
* Relay constructor given a channel.
*
* This code initializes the relay and reserves all resources that need to be
* locked. Initially the relay is set to both lines at 0v.
*
* @param channel The channel number (0-3).
* @param direction The direction that the Relay object will control.
*/
Relay::Relay(int channel, Relay::Direction direction)
: m_channel(channel), m_direction(direction) {
if (!SensorUtil::CheckRelayChannel(m_channel)) {
@@ -90,11 +81,6 @@ Relay::Relay(int channel, Relay::Direction direction)
SetName("Relay", m_channel);
}
/**
* Free the resource associated with a relay.
*
* The relay channels are set to free and the relay output is turned off.
*/
Relay::~Relay() {
int32_t status = 0;
HAL_SetRelay(m_forwardHandle, false, &status);
@@ -104,21 +90,6 @@ Relay::~Relay() {
if (m_reverseHandle != HAL_kInvalidHandle) HAL_FreeRelayPort(m_reverseHandle);
}
/**
* Set the relay state.
*
* Valid values depend on which directions of the relay are controlled by the
* object.
*
* When set to kBothDirections, the relay can be any of the four states:
* 0v-0v, 0v-12v, 12v-0v, 12v-12v
*
* When set to kForwardOnly or kReverseOnly, you can specify the constant for
* the direction or you can simply specify kOff and kOn. Using only kOff and
* kOn is recommended.
*
* @param value The state to set the relay.
*/
void Relay::Set(Relay::Value value) {
if (StatusIsFatal()) return;
@@ -170,16 +141,6 @@ void Relay::Set(Relay::Value value) {
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Get the Relay State
*
* Gets the current state of the relay.
*
* When set to kForwardOnly or kReverseOnly, value is returned as kOn/kOff not
* kForward/kReverse (per the recommendation in Set).
*
* @return The current state of the relay as a Relay::Value
*/
Relay::Value Relay::Get() const {
int32_t status;
@@ -216,54 +177,20 @@ Relay::Value Relay::Get() const {
int Relay::GetChannel() const { return m_channel; }
/**
* Set the expiration time for the Relay object.
*
* @param timeout The timeout (in seconds) for this relay object
*/
void Relay::SetExpiration(double timeout) {
m_safetyHelper->SetExpiration(timeout);
}
/**
* Return the expiration time for the relay object.
*
* @return The expiration time value.
*/
double Relay::GetExpiration() const { return m_safetyHelper->GetExpiration(); }
/**
* Check if the relay object is currently alive or stopped due to a timeout.
*
* @return a bool value that is true if the motor has NOT timed out and should
* still be running.
*/
bool Relay::IsAlive() const { return m_safetyHelper->IsAlive(); }
/**
* Stop the motor associated with this PWM object.
*
* This is called by the MotorSafetyHelper object when it has a timeout for this
* relay and needs to stop it from running.
*/
void Relay::StopMotor() { Set(kOff); }
/**
* Enable/disable motor safety for this device.
*
* Turn on and off the motor safety option for this relay object.
*
* @param enabled True if motor safety is enforced for this object
*/
void Relay::SetSafetyEnabled(bool enabled) {
m_safetyHelper->SetSafetyEnabled(enabled);
}
/**
* Check if motor safety is enabled for this object.
*
* @returns True if motor safety is enforced for this object
*/
bool Relay::IsSafetyEnabled() const {
return m_safetyHelper->IsSafetyEnabled();
}

View File

@@ -14,28 +14,6 @@ using namespace frc;
wpi::mutex Resource::m_createMutex;
/**
* Allocate storage for a new instance of Resource.
*
* Allocate a bool array of values that will get initialized to indicate that no
* resources have been allocated yet. The indicies of the resources are [0 ..
* elements - 1].
*/
Resource::Resource(uint32_t elements) {
m_isAllocated = std::vector<bool>(elements, false);
}
/**
* Factory method to create a Resource allocation-tracker *if* needed.
*
* @param r address of the caller's Resource pointer. If *r == nullptr,
* this will construct a Resource and make *r point to it. If
* *r != nullptr, i.e. the caller already has a Resource
* instance, this won't do anything.
* @param elements the number of elements for this Resource allocator to
* track, that is, it will allocate resource numbers in the
* range [0 .. elements - 1].
*/
void Resource::CreateResourceObject(std::unique_ptr<Resource>& r,
uint32_t elements) {
std::lock_guard<wpi::mutex> lock(m_createMutex);
@@ -44,13 +22,10 @@ void Resource::CreateResourceObject(std::unique_ptr<Resource>& r,
}
}
/**
* Allocate a resource.
*
* When a resource is requested, mark it allocated. In this case, a free
* resource value within the range is located and returned after it is marked
* allocated.
*/
Resource::Resource(uint32_t elements) {
m_isAllocated = std::vector<bool>(elements, false);
}
uint32_t Resource::Allocate(const std::string& resourceDesc) {
std::lock_guard<wpi::mutex> lock(m_allocateMutex);
for (uint32_t i = 0; i < m_isAllocated.size(); i++) {
@@ -63,12 +38,6 @@ uint32_t Resource::Allocate(const std::string& resourceDesc) {
return std::numeric_limits<uint32_t>::max();
}
/**
* Allocate a specific resource value.
*
* The user requests a specific resource value, i.e. channel number and it is
* verified unallocated, then returned.
*/
uint32_t Resource::Allocate(uint32_t index, const std::string& resourceDesc) {
std::lock_guard<wpi::mutex> lock(m_allocateMutex);
if (index >= m_isAllocated.size()) {
@@ -83,13 +52,6 @@ uint32_t Resource::Allocate(uint32_t index, const std::string& resourceDesc) {
return index;
}
/**
* Free an allocated resource.
*
* After a resource is no longer needed, for example a destructor is called for
* a channel assignment class, Free will release the resource value so it can
* be reused somewhere else in the program.
*/
void Resource::Free(uint32_t index) {
std::unique_lock<wpi::mutex> lock(m_allocateMutex);
if (index == std::numeric_limits<uint32_t>::max()) return;

View File

@@ -58,17 +58,20 @@ static void SetupCameraServerShared() {
SetCameraServerShared(std::make_unique<WPILibCameraServerShared>());
}
/**
* Constructor for a generic robot program.
*
* User code should be placed in the constructor that runs before the Autonomous
* or Operator Control period starts. The constructor will run to completion
* before Autonomous is entered.
*
* This must be used to ensure that the communications code starts. In the
* future it would be nice to put this code into it's own task that loads on
* boot so ensure that it runs.
*/
bool RobotBase::IsEnabled() const { return m_ds.IsEnabled(); }
bool RobotBase::IsDisabled() const { return m_ds.IsDisabled(); }
bool RobotBase::IsAutonomous() const { return m_ds.IsAutonomous(); }
bool RobotBase::IsOperatorControl() const { return m_ds.IsOperatorControl(); }
bool RobotBase::IsTest() const { return m_ds.IsTest(); }
bool RobotBase::IsNewDataAvailable() const { return m_ds.IsNewControlData(); }
std::thread::id RobotBase::GetThreadId() { return m_threadId; }
RobotBase::RobotBase() : m_ds(DriverStation::GetInstance()) {
if (!HAL_Initialize(500, 0)) {
wpi::errs() << "FATAL ERROR: HAL could not be initialized\n";
@@ -105,54 +108,3 @@ RobotBase::RobotBase() : m_ds(DriverStation::GetInstance()) {
LiveWindow::GetInstance()->SetEnabled(false);
}
/**
* Determine if the Robot is currently enabled.
*
* @return True if the Robot is currently enabled by the field controls.
*/
bool RobotBase::IsEnabled() const { return m_ds.IsEnabled(); }
/**
* Determine if the Robot is currently disabled.
*
* @return True if the Robot is currently disabled by the field controls.
*/
bool RobotBase::IsDisabled() const { return m_ds.IsDisabled(); }
/**
* Determine if the robot is currently in Autonomous mode.
*
* @return True if the robot is currently operating Autonomously as determined
* by the field controls.
*/
bool RobotBase::IsAutonomous() const { return m_ds.IsAutonomous(); }
/**
* Determine if the robot is currently in Operator Control mode.
*
* @return True if the robot is currently operating in Tele-Op mode as
* determined by the field controls.
*/
bool RobotBase::IsOperatorControl() const { return m_ds.IsOperatorControl(); }
/**
* Determine if the robot is currently in Test mode.
*
* @return True if the robot is currently running tests as determined by the
* field controls.
*/
bool RobotBase::IsTest() const { return m_ds.IsTest(); }
/**
* Indicates if new data is available from the driver station.
*
* @return Has new data arrived over the network since the last time this
* function was called?
*/
bool RobotBase::IsNewDataAvailable() const { return m_ds.IsNewControlData(); }
/**
* Gets the ID of the main robot thread.
*/
std::thread::id RobotBase::GetThreadId() { return m_threadId; }

View File

@@ -11,15 +11,8 @@
#include "ErrorBase.h"
namespace frc {
using namespace frc;
/**
* Return the FPGA Version number.
*
* For now, expect this to be competition year.
*
* @return FPGA Version number.
*/
int RobotController::GetFPGAVersion() {
int32_t status = 0;
int version = HAL_GetFPGAVersion(&status);
@@ -27,15 +20,6 @@ int RobotController::GetFPGAVersion() {
return version;
}
/**
* Return the FPGA Revision number.
*
* The format of the revision is 3 numbers. The 12 most significant bits are the
* Major Revision. The next 8 bits are the Minor Revision. The 12 least
* significant bits are the Build Number.
*
* @return FPGA Revision number.
*/
int64_t RobotController::GetFPGARevision() {
int32_t status = 0;
int64_t revision = HAL_GetFPGARevision(&status);
@@ -43,12 +27,6 @@ int64_t RobotController::GetFPGARevision() {
return revision;
}
/**
* Read the microsecond-resolution timer on the FPGA.
*
* @return The current time in microseconds according to the FPGA (since FPGA
* reset).
*/
uint64_t RobotController::GetFPGATime() {
int32_t status = 0;
uint64_t time = HAL_GetFPGATime(&status);
@@ -56,11 +34,6 @@ uint64_t RobotController::GetFPGATime() {
return time;
}
/**
* Get the state of the "USER" button on the roboRIO.
*
* @return True if the button is currently pressed down
*/
bool RobotController::GetUserButton() {
int32_t status = 0;
@@ -70,14 +43,6 @@ bool RobotController::GetUserButton() {
return value;
}
/**
* Check if the FPGA outputs are enabled.
*
* The outputs may be disabled if the robot is disabled or e-stopped, the
* watchdog has expired, or if the roboRIO browns out.
*
* @return True if the FPGA outputs are enabled.
*/
bool RobotController::IsSysActive() {
int32_t status = 0;
bool retVal = HAL_GetSystemActive(&status);
@@ -85,11 +50,6 @@ bool RobotController::IsSysActive() {
return retVal;
}
/**
* Check if the system is browned out.
*
* @return True if the system is browned out
*/
bool RobotController::IsBrownedOut() {
int32_t status = 0;
bool retVal = HAL_GetBrownedOut(&status);
@@ -97,11 +57,6 @@ bool RobotController::IsBrownedOut() {
return retVal;
}
/**
* Get the input voltage to the robot controller.
*
* @return The controller input voltage value in Volts
*/
double RobotController::GetInputVoltage() {
int32_t status = 0;
double retVal = HAL_GetVinVoltage(&status);
@@ -109,11 +64,6 @@ double RobotController::GetInputVoltage() {
return retVal;
}
/**
* Get the input current to the robot controller.
*
* @return The controller input current value in Amps
*/
double RobotController::GetInputCurrent() {
int32_t status = 0;
double retVal = HAL_GetVinCurrent(&status);
@@ -121,111 +71,6 @@ double RobotController::GetInputCurrent() {
return retVal;
}
/**
* Get the voltage of the 6V rail.
*
* @return The controller 6V rail voltage value in Volts
*/
double RobotController::GetVoltage6V() {
int32_t status = 0;
double retVal = HAL_GetUserVoltage6V(&status);
wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
return retVal;
}
/**
* Get the current output of the 6V rail.
*
* @return The controller 6V rail output current value in Amps
*/
double RobotController::GetCurrent6V() {
int32_t status = 0;
double retVal = HAL_GetUserCurrent6V(&status);
wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
return retVal;
}
/**
* Get the enabled state of the 6V rail. The rail may be disabled due to a
* controller brownout, a short circuit on the rail, or controller over-voltage.
*
* @return The controller 6V rail enabled value. True for enabled.
*/
bool RobotController::GetEnabled6V() {
int32_t status = 0;
bool retVal = HAL_GetUserActive6V(&status);
wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
return retVal;
}
/**
* Get the count of the total current faults on the 6V rail since the controller
* has booted.
*
* @return The number of faults.
*/
int RobotController::GetFaultCount6V() {
int32_t status = 0;
int retVal = HAL_GetUserCurrentFaults6V(&status);
wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
return retVal;
}
/**
* Get the voltage of the 5V rail.
*
* @return The controller 5V rail voltage value in Volts
*/
double RobotController::GetVoltage5V() {
int32_t status = 0;
double retVal = HAL_GetUserVoltage5V(&status);
wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
return retVal;
}
/**
* Get the current output of the 5V rail.
*
* @return The controller 5V rail output current value in Amps
*/
double RobotController::GetCurrent5V() {
int32_t status = 0;
double retVal = HAL_GetUserCurrent5V(&status);
wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
return retVal;
}
/**
* Get the enabled state of the 5V rail. The rail may be disabled due to a
* controller brownout, a short circuit on the rail, or controller over-voltage.
*
* @return The controller 5V rail enabled value. True for enabled.
*/
bool RobotController::GetEnabled5V() {
int32_t status = 0;
bool retVal = HAL_GetUserActive5V(&status);
wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
return retVal;
}
/**
* Get the count of the total current faults on the 5V rail since the controller
* has booted.
*
* @return The number of faults
*/
int RobotController::GetFaultCount5V() {
int32_t status = 0;
int retVal = HAL_GetUserCurrentFaults5V(&status);
wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
return retVal;
}
/**
* Get the voltage of the 3.3V rail.
*
* @return The controller 3.3V rail voltage value in Volts
*/
double RobotController::GetVoltage3V3() {
int32_t status = 0;
double retVal = HAL_GetUserVoltage3V3(&status);
@@ -233,11 +78,6 @@ double RobotController::GetVoltage3V3() {
return retVal;
}
/**
* Get the current output of the 3.3V rail.
*
* @return The controller 3.3V rail output current value in Amps
*/
double RobotController::GetCurrent3V3() {
int32_t status = 0;
double retVal = HAL_GetUserCurrent3V3(&status);
@@ -245,12 +85,6 @@ double RobotController::GetCurrent3V3() {
return retVal;
}
/**
* Get the enabled state of the 3.3V rail. The rail may be disabled due to a
* controller brownout, a short circuit on the rail, or controller over-voltage.
*
* @return The controller 3.3V rail enabled value. True for enabled.
*/
bool RobotController::GetEnabled3V3() {
int32_t status = 0;
bool retVal = HAL_GetUserActive3V3(&status);
@@ -258,12 +92,6 @@ bool RobotController::GetEnabled3V3() {
return retVal;
}
/**
* Get the count of the total current faults on the 3.3V rail since the
* controller has booted.
*
* @return The number of faults
*/
int RobotController::GetFaultCount3V3() {
int32_t status = 0;
int retVal = HAL_GetUserCurrentFaults3V3(&status);
@@ -271,6 +99,62 @@ int RobotController::GetFaultCount3V3() {
return retVal;
}
double RobotController::GetVoltage5V() {
int32_t status = 0;
double retVal = HAL_GetUserVoltage5V(&status);
wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
return retVal;
}
double RobotController::GetCurrent5V() {
int32_t status = 0;
double retVal = HAL_GetUserCurrent5V(&status);
wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
return retVal;
}
bool RobotController::GetEnabled5V() {
int32_t status = 0;
bool retVal = HAL_GetUserActive5V(&status);
wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
return retVal;
}
int RobotController::GetFaultCount5V() {
int32_t status = 0;
int retVal = HAL_GetUserCurrentFaults5V(&status);
wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
return retVal;
}
double RobotController::GetVoltage6V() {
int32_t status = 0;
double retVal = HAL_GetUserVoltage6V(&status);
wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
return retVal;
}
double RobotController::GetCurrent6V() {
int32_t status = 0;
double retVal = HAL_GetUserCurrent6V(&status);
wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
return retVal;
}
bool RobotController::GetEnabled6V() {
int32_t status = 0;
bool retVal = HAL_GetUserActive6V(&status);
wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
return retVal;
}
int RobotController::GetFaultCount6V() {
int32_t status = 0;
int retVal = HAL_GetUserCurrentFaults6V(&status);
wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
return retVal;
}
CANStatus RobotController::GetCANStatus() {
int32_t status = 0;
float percentBusUtilization = 0;
@@ -288,4 +172,3 @@ CANStatus RobotController::GetCANStatus() {
static_cast<int>(txFullCount), static_cast<int>(receiveErrorCount),
static_cast<int>(transmitErrorCount)};
}
} // namespace frc

View File

@@ -25,38 +25,6 @@ static std::shared_ptr<SpeedController> make_shared_nodelete(
return std::shared_ptr<SpeedController>(ptr, NullDeleter<SpeedController>());
}
/*
* Driving functions
* These functions provide an interface to multiple motors that is used for C
* programming.
* The Drive(speed, direction) function is the main part of the set that makes
* it easy to set speeds and direction independently in one call.
*/
/**
* Common function to initialize all the robot drive constructors.
*
* Create a motor safety object (the real reason for the common code) and
* initialize all the motor assignments. The default timeout is set for the
* robot drive.
*/
void RobotDrive::InitRobotDrive() {
m_safetyHelper = std::make_unique<MotorSafetyHelper>(this);
m_safetyHelper->SetSafetyEnabled(true);
}
/**
* Constructor for RobotDrive with 2 motors specified with channel numbers.
*
* Set up parameters for a two wheel drive system where the
* left and right motor pwm channels are specified in the call.
* This call assumes Talons for controlling the motors.
*
* @param leftMotorChannel The PWM channel number that drives the left motor.
* 0-9 are on-board, 10-19 are on the MXP port
* @param rightMotorChannel The PWM channel number that drives the right motor.
* 0-9 are on-board, 10-19 are on the MXP port
*/
RobotDrive::RobotDrive(int leftMotorChannel, int rightMotorChannel) {
InitRobotDrive();
m_rearLeftMotor = std::make_shared<Talon>(leftMotorChannel);
@@ -64,22 +32,6 @@ RobotDrive::RobotDrive(int leftMotorChannel, int rightMotorChannel) {
SetLeftRightMotorOutputs(0.0, 0.0);
}
/**
* Constructor for RobotDrive with 4 motors specified with channel numbers.
*
* Set up parameters for a four wheel drive system where all four motor
* pwm channels are specified in the call.
* This call assumes Talons for controlling the motors.
*
* @param frontLeftMotor Front left motor channel number. 0-9 are on-board,
* 10-19 are on the MXP port
* @param rearLeftMotor Rear Left motor channel number. 0-9 are on-board,
* 10-19 are on the MXP port
* @param frontRightMotor Front right motor channel number. 0-9 are on-board,
* 10-19 are on the MXP port
* @param rearRightMotor Rear Right motor channel number. 0-9 are on-board,
* 10-19 are on the MXP port
*/
RobotDrive::RobotDrive(int frontLeftMotor, int rearLeftMotor,
int frontRightMotor, int rearRightMotor) {
InitRobotDrive();
@@ -90,18 +42,6 @@ RobotDrive::RobotDrive(int frontLeftMotor, int rearLeftMotor,
SetLeftRightMotorOutputs(0.0, 0.0);
}
/**
* Constructor for RobotDrive with 2 motors specified as SpeedController
* objects.
*
* The SpeedController version of the constructor enables programs to use the
* RobotDrive classes with subclasses of the SpeedController objects, for
* example, versions with ramping or reshaping of the curve to suit motor bias
* or deadband elimination.
*
* @param leftMotor The left SpeedController object used to drive the robot.
* @param rightMotor The right SpeedController object used to drive the robot.
*/
RobotDrive::RobotDrive(SpeedController* leftMotor,
SpeedController* rightMotor) {
InitRobotDrive();
@@ -114,7 +54,6 @@ RobotDrive::RobotDrive(SpeedController* leftMotor,
m_rearRightMotor = make_shared_nodelete(rightMotor);
}
// TODO: Change to rvalue references & move syntax.
RobotDrive::RobotDrive(SpeedController& leftMotor,
SpeedController& rightMotor) {
InitRobotDrive();
@@ -134,21 +73,6 @@ RobotDrive::RobotDrive(std::shared_ptr<SpeedController> leftMotor,
m_rearRightMotor = rightMotor;
}
/**
* Constructor for RobotDrive with 4 motors specified as SpeedController
* objects.
*
* Speed controller input version of RobotDrive (see previous comments).
*
* @param frontLeftMotor The front left SpeedController object used to drive
* the robot.
* @param rearLeftMotor The back left SpeedController object used to drive
* the robot.
* @param frontRightMotor The front right SpeedController object used to drive
* the robot.
* @param rearRightMotor The back right SpeedController object used to drive
* the robot.
*/
RobotDrive::RobotDrive(SpeedController* frontLeftMotor,
SpeedController* rearLeftMotor,
SpeedController* frontRightMotor,
@@ -192,28 +116,6 @@ RobotDrive::RobotDrive(std::shared_ptr<SpeedController> frontLeftMotor,
m_rearRightMotor = rearRightMotor;
}
/**
* Drive the motors at "outputMagnitude" and "curve".
* Both outputMagnitude and curve are -1.0 to +1.0 values, where 0.0 represents
* stopped and not turning. curve < 0 will turn left and curve > 0 will turn
* right.
*
* The algorithm for steering provides a constant turn radius for any normal
* speed range, both forward and backward. Increasing m_sensitivity causes
* sharper turns for fixed values of curve.
*
* This function will most likely be used in an autonomous routine.
*
* @param outputMagnitude The speed setting for the outside wheel in a turn,
* forward or backwards, +1 to -1.
* @param curve The rate of turn, constant for different forward
* speeds. Set curve < 0 for left turn or curve > 0 for
* right turn.
*
* Set curve = e^(-r/w) to get a turn radius r for wheelbase w of your robot.
* Conversely, turn radius r = -ln(curve)*w for a given value of curve and
* wheelbase w.
*/
void RobotDrive::Drive(double outputMagnitude, double curve) {
double leftOutput, rightOutput;
static bool reported = false;
@@ -242,17 +144,6 @@ void RobotDrive::Drive(double outputMagnitude, double curve) {
SetLeftRightMotorOutputs(leftOutput, rightOutput);
}
/**
* Provide tank steering using the stored robot configuration.
*
* Drive the robot using two joystick inputs. The Y-axis will be selected from
* each Joystick object.
*
* @param leftStick The joystick to control the left side of the robot.
* @param rightStick The joystick to control the right side of the robot.
* @param squaredInputs If true, the sensitivity will be decreased for small
* values
*/
void RobotDrive::TankDrive(GenericHID* leftStick, GenericHID* rightStick,
bool squaredInputs) {
if (leftStick == nullptr || rightStick == nullptr) {
@@ -262,36 +153,11 @@ void RobotDrive::TankDrive(GenericHID* leftStick, GenericHID* rightStick,
TankDrive(leftStick->GetY(), rightStick->GetY(), squaredInputs);
}
/**
* Provide tank steering using the stored robot configuration.
*
* Drive the robot using two joystick inputs. The Y-axis will be selected from
* each Joystick object.
*
* @param leftStick The joystick to control the left side of the robot.
* @param rightStick The joystick to control the right side of the robot.
* @param squaredInputs If true, the sensitivity will be decreased for small
* values
*/
void RobotDrive::TankDrive(GenericHID& leftStick, GenericHID& rightStick,
bool squaredInputs) {
TankDrive(leftStick.GetY(), rightStick.GetY(), squaredInputs);
}
/**
* Provide tank steering using the stored robot configuration.
*
* This function lets you pick the axis to be used on each Joystick object for
* the left and right sides of the robot.
*
* @param leftStick The Joystick object to use for the left side of the robot.
* @param leftAxis The axis to select on the left side Joystick object.
* @param rightStick The Joystick object to use for the right side of the
* robot.
* @param rightAxis The axis to select on the right side Joystick object.
* @param squaredInputs If true, the sensitivity will be decreased for small
* values
*/
void RobotDrive::TankDrive(GenericHID* leftStick, int leftAxis,
GenericHID* rightStick, int rightAxis,
bool squaredInputs) {
@@ -310,16 +176,6 @@ void RobotDrive::TankDrive(GenericHID& leftStick, int leftAxis,
squaredInputs);
}
/**
* Provide tank steering using the stored robot configuration.
*
* This function lets you directly provide joystick values from any source.
*
* @param leftValue The value of the left stick.
* @param rightValue The value of the right stick.
* @param squaredInputs If true, the sensitivity will be decreased for small
* values
*/
void RobotDrive::TankDrive(double leftValue, double rightValue,
bool squaredInputs) {
static bool reported = false;
@@ -342,58 +198,16 @@ void RobotDrive::TankDrive(double leftValue, double rightValue,
SetLeftRightMotorOutputs(leftValue, rightValue);
}
/**
* Arcade drive implements single stick driving.
*
* Given a single Joystick, the class assumes the Y axis for the move value and
* the X axis for the rotate value.
* (Should add more information here regarding the way that arcade drive works.)
*
* @param stick The joystick to use for Arcade single-stick driving.
* The Y-axis will be selected for forwards/backwards and
* the X-axis will be selected for rotation rate.
* @param squaredInputs If true, the sensitivity will be decreased for small
* values
*/
void RobotDrive::ArcadeDrive(GenericHID* stick, bool squaredInputs) {
// simply call the full-featured ArcadeDrive with the appropriate values
ArcadeDrive(stick->GetY(), stick->GetX(), squaredInputs);
}
/**
* Arcade drive implements single stick driving.
*
* Given a single Joystick, the class assumes the Y axis for the move value and
* the X axis for the rotate value.
* (Should add more information here regarding the way that arcade drive works.)
*
* @param stick The joystick to use for Arcade single-stick driving.
* The Y-axis will be selected for forwards/backwards and
* the X-axis will be selected for rotation rate.
* @param squaredInputs If true, the sensitivity will be decreased for small
* values
*/
void RobotDrive::ArcadeDrive(GenericHID& stick, bool squaredInputs) {
// simply call the full-featured ArcadeDrive with the appropriate values
ArcadeDrive(stick.GetY(), stick.GetX(), squaredInputs);
}
/**
* Arcade drive implements single stick driving.
*
* Given two joystick instances and two axis, compute the values to send to
* either two or four motors.
*
* @param moveStick The Joystick object that represents the
* forward/backward direction
* @param moveAxis The axis on the moveStick object to use for
* forwards/backwards (typically Y_AXIS)
* @param rotateStick The Joystick object that represents the rotation value
* @param rotateAxis The axis on the rotation object to use for the rotate
* right/left (typically X_AXIS)
* @param squaredInputs Setting this parameter to true increases the
* sensitivity at lower speeds
*/
void RobotDrive::ArcadeDrive(GenericHID* moveStick, int moveAxis,
GenericHID* rotateStick, int rotateAxis,
bool squaredInputs) {
@@ -403,22 +217,6 @@ void RobotDrive::ArcadeDrive(GenericHID* moveStick, int moveAxis,
ArcadeDrive(moveValue, rotateValue, squaredInputs);
}
/**
* Arcade drive implements single stick driving.
*
* Given two joystick instances and two axis, compute the values to send to
* either two or four motors.
*
* @param moveStick The Joystick object that represents the
* forward/backward direction
* @param moveAxis The axis on the moveStick object to use for
* forwards/backwards (typically Y_AXIS)
* @param rotateStick The Joystick object that represents the rotation value
* @param rotateAxis The axis on the rotation object to use for the rotate
* right/left (typically X_AXIS)
* @param squaredInputs Setting this parameter to true increases the
* sensitivity at lower speeds
*/
void RobotDrive::ArcadeDrive(GenericHID& moveStick, int moveAxis,
GenericHID& rotateStick, int rotateAxis,
bool squaredInputs) {
@@ -428,15 +226,6 @@ void RobotDrive::ArcadeDrive(GenericHID& moveStick, int moveAxis,
ArcadeDrive(moveValue, rotateValue, squaredInputs);
}
/**
* Arcade drive implements single stick driving.
*
* This function lets you directly provide joystick values from any source.
*
* @param moveValue The value to use for fowards/backwards
* @param rotateValue The value to use for the rotate right/left
* @param squaredInputs If set, increases the sensitivity at low speeds
*/
void RobotDrive::ArcadeDrive(double moveValue, double rotateValue,
bool squaredInputs) {
static bool reported = false;
@@ -480,27 +269,6 @@ void RobotDrive::ArcadeDrive(double moveValue, double rotateValue,
SetLeftRightMotorOutputs(leftMotorOutput, rightMotorOutput);
}
/**
* Drive method for Mecanum wheeled robots.
*
* A method for driving with Mecanum wheeled robots. There are 4 wheels
* on the robot, arranged so that the front and back wheels are toed in 45
* degrees.
* When looking at the wheels from the top, the roller axles should form an X
* across the robot.
*
* This is designed to be directly driven by joystick axes.
*
* @param x The speed that the robot should drive in the X direction.
* [-1.0..1.0]
* @param y The speed that the robot should drive in the Y direction.
* This input is inverted to match the forward == -1.0 that
* joysticks produce. [-1.0..1.0]
* @param rotation The rate of rotation for the robot that is completely
* independent of the translation. [-1.0..1.0]
* @param gyroAngle The current angle reading from the gyro. Use this to
* implement field-oriented controls.
*/
void RobotDrive::MecanumDrive_Cartesian(double x, double y, double rotation,
double gyroAngle) {
static bool reported = false;
@@ -533,23 +301,6 @@ void RobotDrive::MecanumDrive_Cartesian(double x, double y, double rotation,
m_safetyHelper->Feed();
}
/**
* Drive method for Mecanum wheeled robots.
*
* A method for driving with Mecanum wheeled robots. There are 4 wheels
* on the robot, arranged so that the front and back wheels are toed in 45
* degrees.
* When looking at the wheels from the top, the roller axles should form an X
* across the robot.
*
* @param magnitude The speed that the robot should drive in a given direction.
* [-1.0..1.0]
* @param direction The direction the robot should drive in degrees. The
* direction and maginitute are independent of the rotation
* rate.
* @param rotation The rate of rotation for the robot that is completely
* independent of the magnitute or direction. [-1.0..1.0]
*/
void RobotDrive::MecanumDrive_Polar(double magnitude, double direction,
double rotation) {
static bool reported = false;
@@ -582,33 +333,11 @@ void RobotDrive::MecanumDrive_Polar(double magnitude, double direction,
m_safetyHelper->Feed();
}
/**
* Holonomic Drive method for Mecanum wheeled robots.
*
* This is an alias to MecanumDrive_Polar() for backward compatability
*
* @param magnitude The speed that the robot should drive in a given direction.
* [-1.0..1.0]
* @param direction The direction the robot should drive. The direction and
* magnitude are independent of the rotation rate.
* @param rotation The rate of rotation for the robot that is completely
* independent of the magnitude or direction. [-1.0..1.0]
*/
void RobotDrive::HolonomicDrive(double magnitude, double direction,
double rotation) {
MecanumDrive_Polar(magnitude, direction, rotation);
}
/**
* Set the speed of the right and left motors.
*
* This is used once an appropriate drive setup function is called such as
* TwoWheelDrive(). The motors are set to "leftOutput" and "rightOutput"
* and includes flipping the direction of one side for opposing motors.
*
* @param leftOutput The speed to send to the left side of the robot.
* @param rightOutput The speed to send to the right side of the robot.
*/
void RobotDrive::SetLeftRightMotorOutputs(double leftOutput,
double rightOutput) {
wpi_assert(m_rearLeftMotor != nullptr && m_rearRightMotor != nullptr);
@@ -624,57 +353,6 @@ void RobotDrive::SetLeftRightMotorOutputs(double leftOutput,
m_safetyHelper->Feed();
}
/**
* Limit motor values to the -1.0 to +1.0 range.
*/
double RobotDrive::Limit(double number) {
if (number > 1.0) {
return 1.0;
}
if (number < -1.0) {
return -1.0;
}
return number;
}
/**
* Normalize all wheel speeds if the magnitude of any wheel is greater than 1.0.
*/
void RobotDrive::Normalize(double* wheelSpeeds) {
double maxMagnitude = std::fabs(wheelSpeeds[0]);
for (int i = 1; i < kMaxNumberOfMotors; i++) {
double temp = std::fabs(wheelSpeeds[i]);
if (maxMagnitude < temp) maxMagnitude = temp;
}
if (maxMagnitude > 1.0) {
for (int i = 0; i < kMaxNumberOfMotors; i++) {
wheelSpeeds[i] = wheelSpeeds[i] / maxMagnitude;
}
}
}
/**
* Rotate a vector in Cartesian space.
*/
void RobotDrive::RotateVector(double& x, double& y, double angle) {
double cosA = std::cos(angle * (3.14159 / 180.0));
double sinA = std::sin(angle * (3.14159 / 180.0));
double xOut = x * cosA - y * sinA;
double yOut = x * sinA + y * cosA;
x = xOut;
y = yOut;
}
/*
* Invert a motor direction.
*
* This is used when a motor should run in the opposite direction as the drive
* code would normally run it. Motors that are direct drive would be inverted,
* the Drive code assumes that the motors are geared with one reversal.
*
* @param motor The motor index to invert.
* @param isInverted True if the motor should be inverted when operated.
*/
void RobotDrive::SetInvertedMotor(MotorType motor, bool isInverted) {
if (motor < 0 || motor > 3) {
wpi_setWPIError(InvalidMotorIndex);
@@ -696,25 +374,10 @@ void RobotDrive::SetInvertedMotor(MotorType motor, bool isInverted) {
}
}
/**
* Set the turning sensitivity.
*
* This only impacts the Drive() entry-point.
*
* @param sensitivity Effectively sets the turning sensitivity (or turn radius
* for a given value)
*/
void RobotDrive::SetSensitivity(double sensitivity) {
m_sensitivity = sensitivity;
}
/**
* Configure the scaling factor for using RobotDrive with motor controllers in a
* mode other than PercentVbus.
*
* @param maxOutput Multiplied with the output percentage computed by the drive
* functions.
*/
void RobotDrive::SetMaxOutput(double maxOutput) { m_maxOutput = maxOutput; }
void RobotDrive::SetExpiration(double timeout) {
@@ -727,6 +390,14 @@ double RobotDrive::GetExpiration() const {
bool RobotDrive::IsAlive() const { return m_safetyHelper->IsAlive(); }
void RobotDrive::StopMotor() {
if (m_frontLeftMotor != nullptr) m_frontLeftMotor->StopMotor();
if (m_frontRightMotor != nullptr) m_frontRightMotor->StopMotor();
if (m_rearLeftMotor != nullptr) m_rearLeftMotor->StopMotor();
if (m_rearRightMotor != nullptr) m_rearRightMotor->StopMotor();
m_safetyHelper->Feed();
}
bool RobotDrive::IsSafetyEnabled() const {
return m_safetyHelper->IsSafetyEnabled();
}
@@ -739,10 +410,39 @@ void RobotDrive::GetDescription(wpi::raw_ostream& desc) const {
desc << "RobotDrive";
}
void RobotDrive::StopMotor() {
if (m_frontLeftMotor != nullptr) m_frontLeftMotor->StopMotor();
if (m_frontRightMotor != nullptr) m_frontRightMotor->StopMotor();
if (m_rearLeftMotor != nullptr) m_rearLeftMotor->StopMotor();
if (m_rearRightMotor != nullptr) m_rearRightMotor->StopMotor();
m_safetyHelper->Feed();
void RobotDrive::InitRobotDrive() {
m_safetyHelper = std::make_unique<MotorSafetyHelper>(this);
m_safetyHelper->SetSafetyEnabled(true);
}
double RobotDrive::Limit(double number) {
if (number > 1.0) {
return 1.0;
}
if (number < -1.0) {
return -1.0;
}
return number;
}
void RobotDrive::Normalize(double* wheelSpeeds) {
double maxMagnitude = std::fabs(wheelSpeeds[0]);
for (int i = 1; i < kMaxNumberOfMotors; i++) {
double temp = std::fabs(wheelSpeeds[i]);
if (maxMagnitude < temp) maxMagnitude = temp;
}
if (maxMagnitude > 1.0) {
for (int i = 0; i < kMaxNumberOfMotors; i++) {
wheelSpeeds[i] = wheelSpeeds[i] / maxMagnitude;
}
}
}
void RobotDrive::RotateVector(double& x, double& y, double angle) {
double cosA = std::cos(angle * (3.14159 / 180.0));
double sinA = std::sin(angle * (3.14159 / 180.0));
double xOut = x * cosA - y * sinA;
double yOut = x * sinA + y * cosA;
x = xOut;
y = yOut;
}

View File

@@ -11,28 +11,20 @@
using namespace frc;
/**
* Note that the SD540 uses the following bounds for PWM values. These values
* should work reasonably well for most controllers, but if users experience
* issues such as asymmetric behavior around the deadband or inability to
* saturate the controller in either direction, calibration is recommended.
* The calibration procedure can be found in the SD540 User Manual available
* from Mindsensors.
*
* 2.05ms = full "forward"
* 1.55ms = the "high end" of the deadband range
* 1.50ms = center of the deadband range (off)
* 1.44ms = the "low end" of the deadband range
* 0.94ms = full "reverse"
*/
/**
* Constructor for a SD540.
*
* @param channel The PWM channel that the SD540 is attached to. 0-9 are
* on-board, 10-19 are on the MXP port
*/
SD540::SD540(int channel) : PWMSpeedController(channel) {
/* Note that the SD540 uses the following bounds for PWM values. These values
* should work reasonably well for most controllers, but if users experience
* issues such as asymmetric behavior around the deadband or inability to
* saturate the controller in either direction, calibration is recommended.
* The calibration procedure can be found in the SD540 User Manual available
* from Mindsensors.
*
* 2.05ms = full "forward"
* 1.55ms = the "high end" of the deadband range
* 1.50ms = center of the deadband range (off)
* 1.44ms = the "low end" of the deadband range
* 0.94ms = full "reverse"
*/
SetBounds(2.05, 1.55, 1.50, 1.44, .94);
SetPeriodMultiplier(kPeriodMultiplier_1X);
SetSpeed(0.0);

View File

@@ -126,11 +126,6 @@ void SPI::Accumulator::Update() {
} while (!done);
}
/**
* Constructor
*
* @param port the physical SPI port
*/
SPI::SPI(Port port) : m_port(static_cast<HAL_SPIPort>(port)) {
int32_t status = 0;
HAL_InitializeSPI(m_port, &status);
@@ -141,137 +136,68 @@ SPI::SPI(Port port) : m_port(static_cast<HAL_SPIPort>(port)) {
HAL_Report(HALUsageReporting::kResourceType_SPI, instances);
}
/**
* Destructor.
*/
SPI::~SPI() { HAL_CloseSPI(m_port); }
/**
* Configure the rate of the generated clock signal.
*
* The default value is 500,000Hz.
* The maximum value is 4,000,000Hz.
*
* @param hz The clock rate in Hertz.
*/
void SPI::SetClockRate(double hz) { HAL_SetSPISpeed(m_port, hz); }
/**
* Configure the order that bits are sent and received on the wire
* to be most significant bit first.
*/
void SPI::SetMSBFirst() {
m_msbFirst = true;
HAL_SetSPIOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clk_idle_high);
}
/**
* Configure the order that bits are sent and received on the wire
* to be least significant bit first.
*/
void SPI::SetLSBFirst() {
m_msbFirst = false;
HAL_SetSPIOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clk_idle_high);
}
/**
* Configure that the data is stable on the leading edge and the data
* changes on the trailing edge.
*/
void SPI::SetSampleDataOnLeadingEdge() {
m_sampleOnTrailing = false;
HAL_SetSPIOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clk_idle_high);
}
/**
* Configure that the data is stable on the trailing edge and the data
* changes on the leading edge.
*/
void SPI::SetSampleDataOnTrailingEdge() {
m_sampleOnTrailing = true;
HAL_SetSPIOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clk_idle_high);
}
/**
* Configure that the data is stable on the falling edge and the data
* changes on the rising edge.
*/
void SPI::SetSampleDataOnFalling() {
m_sampleOnTrailing = true;
HAL_SetSPIOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clk_idle_high);
}
/**
* Configure that the data is stable on the rising edge and the data
* changes on the falling edge.
*/
void SPI::SetSampleDataOnRising() {
m_sampleOnTrailing = false;
HAL_SetSPIOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clk_idle_high);
}
/**
* Configure the clock output line to be active low.
* This is sometimes called clock polarity high or clock idle high.
*/
void SPI::SetClockActiveLow() {
m_clk_idle_high = true;
HAL_SetSPIOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clk_idle_high);
}
/**
* Configure the clock output line to be active high.
* This is sometimes called clock polarity low or clock idle low.
*/
void SPI::SetClockActiveHigh() {
m_clk_idle_high = false;
HAL_SetSPIOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clk_idle_high);
}
/**
* Configure the chip select line to be active high.
*/
void SPI::SetChipSelectActiveHigh() {
int32_t status = 0;
HAL_SetSPIChipSelectActiveHigh(m_port, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Configure the chip select line to be active low.
*/
void SPI::SetChipSelectActiveLow() {
int32_t status = 0;
HAL_SetSPIChipSelectActiveLow(m_port, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Write data to the slave device. Blocks until there is space in the
* output FIFO.
*
* If not running in output only mode, also saves the data received
* on the MISO input during the transfer into the receive FIFO.
*/
int SPI::Write(uint8_t* data, int size) {
int retVal = 0;
retVal = HAL_WriteSPI(m_port, data, size);
return retVal;
}
/**
* Read a word from the receive FIFO.
*
* Waits for the current transfer to complete if the receive FIFO is empty.
*
* If the receive FIFO is empty, there is no active transfer, and initiate
* is false, errors.
*
* @param initiate If true, this function pushes "0" into the transmit buffer
* and initiates a transfer. If false, this function assumes
* that data is already in the receive FIFO from a previous
* write.
*/
int SPI::Read(bool initiate, uint8_t* dataReceived, int size) {
int retVal = 0;
if (initiate) {
@@ -284,51 +210,24 @@ int SPI::Read(bool initiate, uint8_t* dataReceived, int size) {
return retVal;
}
/**
* Perform a simultaneous read/write transaction with the device
*
* @param dataToSend The data to be written out to the device
* @param dataReceived Buffer to receive data from the device
* @param size The length of the transaction, in bytes
*/
int SPI::Transaction(uint8_t* dataToSend, uint8_t* dataReceived, int size) {
int retVal = 0;
retVal = HAL_TransactionSPI(m_port, dataToSend, dataReceived, size);
return retVal;
}
/**
* Initialize automatic SPI transfer engine.
*
* Only a single engine is available, and use of it blocks use of all other
* chip select usage on the same physical SPI port while it is running.
*
* @param bufferSize buffer size in bytes
*/
void SPI::InitAuto(int bufferSize) {
int32_t status = 0;
HAL_InitSPIAuto(m_port, bufferSize, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Frees the automatic SPI transfer engine.
*/
void SPI::FreeAuto() {
int32_t status = 0;
HAL_FreeSPIAuto(m_port, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Set the data to be transmitted by the engine.
*
* Up to 16 bytes are configurable, and may be followed by up to 127 zero
* bytes.
*
* @param dataToSend data to send (maximum 16 bytes)
* @param zeroSize number of zeros to send after the data
*/
void SPI::SetAutoTransmitData(wpi::ArrayRef<uint8_t> dataToSend, int zeroSize) {
int32_t status = 0;
HAL_SetSPIAutoTransmitData(m_port, dataToSend.data(), dataToSend.size(),
@@ -336,30 +235,12 @@ void SPI::SetAutoTransmitData(wpi::ArrayRef<uint8_t> dataToSend, int zeroSize) {
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Start running the automatic SPI transfer engine at a periodic rate.
*
* InitAuto() and SetAutoTransmitData() must be called before calling this
* function.
*
* @param period period between transfers, in seconds (us resolution)
*/
void SPI::StartAutoRate(double period) {
int32_t status = 0;
HAL_StartSPIAutoRate(m_port, period, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Start running the automatic SPI transfer engine when a trigger occurs.
*
* InitAuto() and SetAutoTransmitData() must be called before calling this
* function.
*
* @param source digital source for the trigger (may be an analog trigger)
* @param rising trigger on the rising edge
* @param falling trigger on the falling edge
*/
void SPI::StartAutoTrigger(DigitalSource& source, bool rising, bool falling) {
int32_t status = 0;
HAL_StartSPIAutoTrigger(
@@ -369,38 +250,18 @@ void SPI::StartAutoTrigger(DigitalSource& source, bool rising, bool falling) {
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Stop running the automatic SPI transfer engine.
*/
void SPI::StopAuto() {
int32_t status = 0;
HAL_StopSPIAuto(m_port, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Force the engine to make a single transfer.
*/
void SPI::ForceAutoRead() {
int32_t status = 0;
HAL_ForceSPIAutoRead(m_port, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Read data that has been transferred by the automatic SPI transfer engine.
*
* Transfers may be made a byte at a time, so it's necessary for the caller
* to handle cases where an entire transfer has not been completed.
*
* Blocks until numToRead bytes have been read or timeout expires.
* May be called with numToRead=0 to retrieve how many bytes are available.
*
* @param buffer buffer where read bytes are stored
* @param numToRead number of bytes to read
* @param timeout timeout in seconds (ms resolution)
* @return Number of bytes remaining to be read
*/
int SPI::ReadAutoReceivedData(uint8_t* buffer, int numToRead, double timeout) {
int32_t status = 0;
int32_t val =
@@ -409,12 +270,6 @@ int SPI::ReadAutoReceivedData(uint8_t* buffer, int numToRead, double timeout) {
return val;
}
/**
* Get the number of bytes dropped by the automatic SPI transfer engine due
* to the receive buffer being full.
*
* @return Number of bytes dropped
*/
int SPI::GetAutoDroppedCount() {
int32_t status = 0;
int32_t val = HAL_GetSPIAutoDroppedCount(m_port, &status);
@@ -422,21 +277,6 @@ int SPI::GetAutoDroppedCount() {
return val;
}
/**
* Initialize the accumulator.
*
* @param period Time between reads
* @param cmd SPI command to send to request data
* @param xferSize SPI transfer size, in bytes
* @param validMask Mask to apply to received data for validity checking
* @param validData After valid_mask is applied, required matching value for
* validity checking
* @param dataShift Bit shift to apply to received data to get actual data
* value
* @param dataSize Size (in bits) of data field
* @param isSigned Is data field signed?
* @param bigEndian Is device big endian?
*/
void SPI::InitAccumulator(double period, int cmd, int xferSize, int validMask,
int validValue, int dataShift, int dataSize,
bool isSigned, bool bigEndian) {
@@ -464,17 +304,11 @@ void SPI::InitAccumulator(double period, int cmd, int xferSize, int validMask,
m_accum->m_notifier.StartPeriodic(period * kAccumulateDepth / 2);
}
/**
* Frees the accumulator.
*/
void SPI::FreeAccumulator() {
m_accum.reset(nullptr);
FreeAuto();
}
/**
* Resets the accumulator to zero.
*/
void SPI::ResetAccumulator() {
if (!m_accum) return;
std::lock_guard<wpi::mutex> lock(m_accum->m_mutex);
@@ -483,32 +317,18 @@ void SPI::ResetAccumulator() {
m_accum->m_lastValue = 0;
}
/**
* Set the center value of the accumulator.
*
* The center value is subtracted from each value before it is added to the
* accumulator. This is used for the center value of devices like gyros and
* accelerometers to make integration work and to take the device offset into
* account when integrating.
*/
void SPI::SetAccumulatorCenter(int center) {
if (!m_accum) return;
std::lock_guard<wpi::mutex> lock(m_accum->m_mutex);
m_accum->m_center = center;
}
/**
* Set the accumulator's deadband.
*/
void SPI::SetAccumulatorDeadband(int deadband) {
if (!m_accum) return;
std::lock_guard<wpi::mutex> lock(m_accum->m_mutex);
m_accum->m_deadband = deadband;
}
/**
* Read the last value read by the accumulator engine.
*/
int SPI::GetAccumulatorLastValue() const {
if (!m_accum) return 0;
std::lock_guard<wpi::mutex> lock(m_accum->m_mutex);
@@ -516,11 +336,6 @@ int SPI::GetAccumulatorLastValue() const {
return m_accum->m_lastValue;
}
/**
* Read the accumulated value.
*
* @return The 64-bit value accumulated since the last Reset().
*/
int64_t SPI::GetAccumulatorValue() const {
if (!m_accum) return 0;
std::lock_guard<wpi::mutex> lock(m_accum->m_mutex);
@@ -528,14 +343,6 @@ int64_t SPI::GetAccumulatorValue() const {
return m_accum->m_value;
}
/**
* Read the number of accumulated values.
*
* Read the count of the accumulated values since the accumulator was last
* Reset().
*
* @return The number of times samples from the channel were accumulated.
*/
int64_t SPI::GetAccumulatorCount() const {
if (!m_accum) return 0;
std::lock_guard<wpi::mutex> lock(m_accum->m_mutex);
@@ -543,11 +350,6 @@ int64_t SPI::GetAccumulatorCount() const {
return m_accum->m_count;
}
/**
* Read the average of the accumulated value.
*
* @return The accumulated average value (value / count).
*/
double SPI::GetAccumulatorAverage() const {
if (!m_accum) return 0;
std::lock_guard<wpi::mutex> lock(m_accum->m_mutex);
@@ -556,15 +358,6 @@ double SPI::GetAccumulatorAverage() const {
return static_cast<double>(m_accum->m_value) / m_accum->m_count;
}
/**
* Read the accumulated value and the number of accumulated values atomically.
*
* This function reads the value and count atomically.
* This can be used for averaging.
*
* @param value Pointer to the 64-bit accumulated output.
* @param count Pointer to the number of accumulation cycles.
*/
void SPI::GetAccumulatorOutput(int64_t& value, int64_t& count) const {
if (!m_accum) {
value = 0;

View File

@@ -9,67 +9,27 @@
using namespace frc;
/**
* Constructor for a SafePWM object taking a channel number.
*
* @param channel The PWM channel number 0-9 are on-board, 10-19 are on the MXP
* port
*/
SafePWM::SafePWM(int channel) : PWM(channel) {
m_safetyHelper = std::make_unique<MotorSafetyHelper>(this);
m_safetyHelper->SetSafetyEnabled(false);
}
/**
* Set the expiration time for the PWM object.
*
* @param timeout The timeout (in seconds) for this motor object
*/
void SafePWM::SetExpiration(double timeout) {
m_safetyHelper->SetExpiration(timeout);
}
/**
* Return the expiration time for the PWM object.
*
* @returns The expiration time value.
*/
double SafePWM::GetExpiration() const {
return m_safetyHelper->GetExpiration();
}
/**
* Check if the PWM object is currently alive or stopped due to a timeout.
*
* @return a bool value that is true if the motor has NOT timed out and should
* still be running.
*/
bool SafePWM::IsAlive() const { return m_safetyHelper->IsAlive(); }
/**
* Stop the motor associated with this PWM object.
*
* This is called by the MotorSafetyHelper object when it has a timeout for this
* PWM and needs to stop it from running.
*/
void SafePWM::StopMotor() { SetDisabled(); }
/**
* Enable/disable motor safety for this device.
*
* Turn on and off the motor safety option for this PWM object.
*
* @param enabled True if motor safety is enforced for this object
*/
void SafePWM::SetSafetyEnabled(bool enabled) {
m_safetyHelper->SetSafetyEnabled(enabled);
}
/**
* Check if motor safety is enabled for this object.
*
* @returns True if motor safety is enforced for this object
*/
bool SafePWM::IsSafetyEnabled() const {
return m_safetyHelper->IsSafetyEnabled();
}
@@ -78,14 +38,6 @@ void SafePWM::GetDescription(wpi::raw_ostream& desc) const {
desc << "PWM " << GetChannel();
}
/**
* Feed the MotorSafety timer when setting the speed.
*
* This method is called by the subclass motor whenever it updates its speed,
* thereby reseting the timeout value.
*
* @param speed Value to pass to the PWM class
*/
void SafePWM::SetSpeed(double speed) {
PWM::SetSpeed(speed);
m_safetyHelper->Feed();

View File

@@ -16,16 +16,6 @@
using namespace frc;
/**
* Start a competition.
*
* This code needs to track the order of the field starting to ensure that
* everything happens in the right order. Repeatedly run the correct method,
* either Autonomous or OperatorControl or Test when the robot is enabled.
* After running the correct method, wait for some state to change, either the
* other mode starts or the robot is disabled. Then go back and wait for the
* robot to be enabled again.
*/
void SampleRobot::StartCompetition() {
LiveWindow* lw = LiveWindow::GetInstance();
@@ -65,77 +55,26 @@ void SampleRobot::StartCompetition() {
}
}
/**
* Robot-wide initialization code should go here.
*
* Users should override this method for default Robot-wide initialization which
* will be called when the robot is first powered on. It will be called exactly
* one time.
*
* Warning: the Driver Station "Robot Code" light and FMS "Robot Ready"
* indicators will be off until RobotInit() exits. Code in RobotInit() that
* waits for enable will cause the robot to never indicate that the code is
* ready, causing the robot to be bypassed in a match.
*/
void SampleRobot::RobotInit() {
wpi::outs() << "Default " << __FUNCTION__ << "() method... Overload me!\n";
}
/**
* Disabled should go here.
*
* Programmers should override this method to run code that should run while the
* field is disabled.
*/
void SampleRobot::Disabled() {
wpi::outs() << "Default " << __FUNCTION__ << "() method... Overload me!\n";
}
/**
* Autonomous should go here.
*
* Programmers should override this method to run code that should run while the
* field is in the autonomous period. This will be called once each time the
* robot enters the autonomous state.
*/
void SampleRobot::Autonomous() {
wpi::outs() << "Default " << __FUNCTION__ << "() method... Overload me!\n";
}
/**
* Operator control (tele-operated) code should go here.
*
* Programmers should override this method to run code that should run while the
* field is in the Operator Control (tele-operated) period. This is called once
* each time the robot enters the teleop state.
*/
void SampleRobot::OperatorControl() {
wpi::outs() << "Default " << __FUNCTION__ << "() method... Overload me!\n";
}
/**
* Test program should go here.
*
* Programmers should override this method to run code that executes while the
* robot is in test mode. This will be called once whenever the robot enters
* test mode
*/
void SampleRobot::Test() {
wpi::outs() << "Default " << __FUNCTION__ << "() method... Overload me!\n";
}
/**
* Robot main program for free-form programs.
*
* This should be overridden by user subclasses if the intent is to not use the
* Autonomous() and OperatorControl() methods. In that case, the program is
* responsible for sensing when to run the autonomous and operator control
* functions in their program.
*
* This method will be called immediately after the constructor is called. If it
* has not been overridden by a user subclass (i.e. the default version runs),
* then the Autonomous() and OperatorControl() methods will be called.
*/
void SampleRobot::RobotMain() { m_robotMainOverridden = false; }
SampleRobot::SampleRobot() {

View File

@@ -27,89 +27,36 @@ const int SensorUtil::kPwmChannels = HAL_GetNumPWMChannels();
const int SensorUtil::kRelayChannels = HAL_GetNumRelayHeaders();
const int SensorUtil::kPDPChannels = HAL_GetNumPDPChannels();
/**
* Check that the solenoid module number is valid.
*
* @return Solenoid module is valid and present
*/
int SensorUtil::GetDefaultSolenoidModule() { return 0; }
bool SensorUtil::CheckSolenoidModule(int moduleNumber) {
return HAL_CheckSolenoidModule(moduleNumber);
}
/**
* Check that the digital channel number is valid.
*
* Verify that the channel number is one of the legal channel numbers. Channel
* numbers are 1-based.
*
* @return Digital channel is valid
*/
bool SensorUtil::CheckDigitalChannel(int channel) {
return HAL_CheckDIOChannel(channel);
}
/**
* Check that the relay channel number is valid.
*
* Verify that the channel number is one of the legal channel numbers. Channel
* numbers are 0-based.
*
* @return Relay channel is valid
*/
bool SensorUtil::CheckRelayChannel(int channel) {
return HAL_CheckRelayChannel(channel);
}
/**
* Check that the digital channel number is valid.
*
* Verify that the channel number is one of the legal channel numbers. Channel
* numbers are 1-based.
*
* @return PWM channel is valid
*/
bool SensorUtil::CheckPWMChannel(int channel) {
return HAL_CheckPWMChannel(channel);
}
/**
* Check that the analog input number is value.
*
* Verify that the analog input number is one of the legal channel numbers.
* Channel numbers are 0-based.
*
* @return Analog channel is valid
*/
bool SensorUtil::CheckAnalogInputChannel(int channel) {
return HAL_CheckAnalogInputChannel(channel);
}
/**
* Check that the analog output number is valid.
*
* Verify that the analog output number is one of the legal channel numbers.
* Channel numbers are 0-based.
*
* @return Analog channel is valid
*/
bool SensorUtil::CheckAnalogOutputChannel(int channel) {
return HAL_CheckAnalogOutputChannel(channel);
}
/**
* Verify that the solenoid channel number is within limits.
*
* @return Solenoid channel is valid
*/
bool SensorUtil::CheckSolenoidChannel(int channel) {
return HAL_CheckSolenoidChannel(channel);
}
/**
* Verify that the power distribution channel number is within limits.
*
* @return PDP channel is valid
*/
bool SensorUtil::CheckPDPChannel(int channel) {
return HAL_CheckPDPModule(channel);
}

View File

@@ -15,17 +15,6 @@
using namespace frc;
/**
* Create an instance of a Serial Port class.
*
* @param baudRate The baud rate to configure the serial port.
* @param port The physical port to use
* @param dataBits The number of data bits per transfer. Valid values are
* between 5 and 8 bits.
* @param parity Select the type of parity checking to use.
* @param stopBits The number of stop bits to use as defined by the enum
* StopBits.
*/
SerialPort::SerialPort(int baudRate, Port port, int dataBits,
SerialPort::Parity parity,
SerialPort::StopBits stopBits) {
@@ -61,18 +50,6 @@ SerialPort::SerialPort(int baudRate, Port port, int dataBits,
HAL_Report(HALUsageReporting::kResourceType_SerialPort, 0);
}
/**
* Create an instance of a Serial Port class.
*
* @param baudRate The baud rate to configure the serial port.
* @param port The physical port to use
* @param portName The direct port name to use
* @param dataBits The number of data bits per transfer. Valid values are
* between 5 and 8 bits.
* @param parity Select the type of parity checking to use.
* @param stopBits The number of stop bits to use as defined by the enum
* StopBits.
*/
SerialPort::SerialPort(int baudRate, const wpi::Twine& portName, Port port,
int dataBits, SerialPort::Parity parity,
SerialPort::StopBits stopBits) {
@@ -112,20 +89,12 @@ SerialPort::SerialPort(int baudRate, const wpi::Twine& portName, Port port,
HAL_Report(HALUsageReporting::kResourceType_SerialPort, 0);
}
/**
* Destructor.
*/
SerialPort::~SerialPort() {
int32_t status = 0;
HAL_CloseSerial(static_cast<HAL_SerialPort>(m_port), &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Set the type of flow control to enable on this port.
*
* By default, flow control is disabled.
*/
void SerialPort::SetFlowControl(SerialPort::FlowControl flowControl) {
int32_t status = 0;
HAL_SetSerialFlowControl(static_cast<HAL_SerialPort>(m_port), flowControl,
@@ -133,15 +102,6 @@ void SerialPort::SetFlowControl(SerialPort::FlowControl flowControl) {
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Enable termination and specify the termination character.
*
* Termination is currently only implemented for receive.
* When the the terminator is recieved, the Read() or Scanf() will return
* fewer bytes than requested, stopping after the terminator.
*
* @param terminator The character to use for termination.
*/
void SerialPort::EnableTermination(char terminator) {
int32_t status = 0;
HAL_EnableSerialTermination(static_cast<HAL_SerialPort>(m_port), terminator,
@@ -149,20 +109,12 @@ void SerialPort::EnableTermination(char terminator) {
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Disable termination behavior.
*/
void SerialPort::DisableTermination() {
int32_t status = 0;
HAL_DisableSerialTermination(static_cast<HAL_SerialPort>(m_port), &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Get the number of bytes currently available to read from the serial port.
*
* @return The number of bytes available to read
*/
int SerialPort::GetBytesReceived() {
int32_t status = 0;
int retVal =
@@ -171,13 +123,6 @@ int SerialPort::GetBytesReceived() {
return retVal;
}
/**
* Read raw bytes out of the buffer.
*
* @param buffer Pointer to the buffer to store the bytes in.
* @param count The maximum number of bytes to read.
* @return The number of bytes actually read into the buffer.
*/
int SerialPort::Read(char* buffer, int count) {
int32_t status = 0;
int retVal = HAL_ReadSerial(static_cast<HAL_SerialPort>(m_port), buffer,
@@ -186,26 +131,10 @@ int SerialPort::Read(char* buffer, int count) {
return retVal;
}
/**
* Write raw bytes to the buffer.
*
* @param buffer Pointer to the buffer to read the bytes from.
* @param count The maximum number of bytes to write.
* @return The number of bytes actually written into the port.
*/
int SerialPort::Write(const char* buffer, int count) {
return Write(wpi::StringRef(buffer, static_cast<size_t>(count)));
}
/**
* Write raw bytes to the buffer.
*
* Use Write({data, len}) to get a buffer that is shorter than the length of the
* string.
*
* @param buffer StringRef to the buffer to read the bytes from.
* @return The number of bytes actually written into the port.
*/
int SerialPort::Write(wpi::StringRef buffer) {
int32_t status = 0;
int retVal = HAL_WriteSerial(static_cast<HAL_SerialPort>(m_port),
@@ -214,32 +143,12 @@ int SerialPort::Write(wpi::StringRef buffer) {
return retVal;
}
/**
* Configure the timeout of the serial port.
*
* This defines the timeout for transactions with the hardware.
* It will affect reads and very large writes.
*
* @param timeout The number of seconds to to wait for I/O.
*/
void SerialPort::SetTimeout(double timeout) {
int32_t status = 0;
HAL_SetSerialTimeout(static_cast<HAL_SerialPort>(m_port), timeout, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Specify the size of the input buffer.
*
* Specify the amount of data that can be stored before data
* from the device is returned to Read or Scanf. If you want
* data that is recieved to be returned immediately, set this to 1.
*
* It the buffer is not filled before the read timeout expires, all
* data that has been received so far will be returned.
*
* @param size The read buffer size.
*/
void SerialPort::SetReadBufferSize(int size) {
int32_t status = 0;
HAL_SetSerialReadBufferSize(static_cast<HAL_SerialPort>(m_port), size,
@@ -247,14 +156,6 @@ void SerialPort::SetReadBufferSize(int size) {
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Specify the size of the output buffer.
*
* Specify the amount of data that can be stored before being
* transmitted to the device.
*
* @param size The write buffer size.
*/
void SerialPort::SetWriteBufferSize(int size) {
int32_t status = 0;
HAL_SetSerialWriteBufferSize(static_cast<HAL_SerialPort>(m_port), size,
@@ -262,40 +163,18 @@ void SerialPort::SetWriteBufferSize(int size) {
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Specify the flushing behavior of the output buffer.
*
* When set to kFlushOnAccess, data is synchronously written to the serial port
* after each call to either Printf() or Write().
*
* When set to kFlushWhenFull, data will only be written to the serial port when
* the buffer is full or when Flush() is called.
*
* @param mode The write buffer mode.
*/
void SerialPort::SetWriteBufferMode(SerialPort::WriteBufferMode mode) {
int32_t status = 0;
HAL_SetSerialWriteMode(static_cast<HAL_SerialPort>(m_port), mode, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Force the output buffer to be written to the port.
*
* This is used when SetWriteBufferMode() is set to kFlushWhenFull to force a
* flush before the buffer is full.
*/
void SerialPort::Flush() {
int32_t status = 0;
HAL_FlushSerial(static_cast<HAL_SerialPort>(m_port), &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Reset the serial port driver to a known state.
*
* Empty the transmit and receive buffers in the device and formatted I/O.
*/
void SerialPort::Reset() {
int32_t status = 0;
HAL_ClearSerial(static_cast<HAL_SerialPort>(m_port), &status);

View File

@@ -19,10 +19,6 @@ constexpr double Servo::kMinServoAngle;
constexpr double Servo::kDefaultMaxServoPWM;
constexpr double Servo::kDefaultMinServoPWM;
/**
* @param channel The PWM channel to which the servo is attached. 0-9 are
* on-board, 10-19 are on the MXP port
*/
Servo::Servo(int channel) : SafePWM(channel) {
// Set minimum and maximum PWM values supported by the servo
SetBounds(kDefaultMaxServoPWM, 0.0, 0.0, 0.0, kDefaultMinServoPWM);
@@ -34,47 +30,12 @@ Servo::Servo(int channel) : SafePWM(channel) {
SetName("Servo", channel);
}
/**
* Set the servo position.
*
* Servo values range from 0.0 to 1.0 corresponding to the range of full left to
* full right.
*
* @param value Position from 0.0 to 1.0.
*/
void Servo::Set(double value) { SetPosition(value); }
/**
* Set the servo to offline.
*
* Set the servo raw value to 0 (undriven)
*/
void Servo::SetOffline() { SetRaw(0); }
/**
* Get the servo position.
*
* Servo values range from 0.0 to 1.0 corresponding to the range of full left to
* full right.
*
* @return Position from 0.0 to 1.0.
*/
double Servo::Get() const { return GetPosition(); }
/**
* Set the servo angle.
*
* Assume that the servo angle is linear with respect to the PWM value (big
* assumption, need to test).
*
* Servo angles that are out of the supported range of the servo simply
* "saturate" in that direction. In other words, if the servo has a range of
* (X degrees to Y degrees) than angles of less than X result in an angle of
* X being set and angles of more than Y degrees result in an angle of Y being
* set.
*
* @param degrees The angle in degrees to set the servo.
*/
void Servo::SetAngle(double degrees) {
if (degrees < kMinServoAngle) {
degrees = kMinServoAngle;
@@ -85,20 +46,20 @@ void Servo::SetAngle(double degrees) {
SetPosition((degrees - kMinServoAngle) / GetServoAngleRange());
}
/**
* Get the servo angle.
*
* Assume that the servo angle is linear with respect to the PWM value (big
* assumption, need to test).
*
* @return The angle in degrees to which the servo is set.
*/
double Servo::GetAngle() const {
return GetPosition() * GetServoAngleRange() + kMinServoAngle;
}
double Servo::GetMaxAngle() const { return kMaxServoAngle; }
double Servo::GetMinAngle() const { return kMinServoAngle; }
void Servo::InitSendable(SendableBuilder& builder) {
builder.SetSmartDashboardType("Servo");
builder.AddDoubleProperty("Value", [=]() { return Get(); },
[=](double value) { Set(value); });
}
double Servo::GetServoAngleRange() const {
return kMaxServoAngle - kMinServoAngle;
}

View File

@@ -11,18 +11,10 @@
using namespace frc;
/**
* Creates an instance of the sensor base.
*
* @param addLiveWindow if true, add this Sendable to LiveWindow
*/
SendableBase::SendableBase(bool addLiveWindow) {
if (addLiveWindow) LiveWindow::GetInstance()->Add(this);
}
/**
* Free the resources used by this object.
*/
SendableBase::~SendableBase() { LiveWindow::GetInstance()->Remove(this); }
std::string SendableBase::GetName() const {
@@ -45,44 +37,18 @@ void SendableBase::SetSubsystem(const wpi::Twine& subsystem) {
m_subsystem = subsystem.str();
}
/**
* Add a child component.
*
* @param child child component
*/
void SendableBase::AddChild(std::shared_ptr<Sendable> child) {
LiveWindow::GetInstance()->AddChild(this, child);
}
/**
* Add a child component.
*
* @param child child component
*/
void SendableBase::AddChild(void* child) {
LiveWindow::GetInstance()->AddChild(this, child);
}
/**
* Sets the name of the sensor with a channel number.
*
* @param moduleType A string that defines the module name in the label for the
* value
* @param channel The channel number the device is plugged into
*/
void SendableBase::SetName(const wpi::Twine& moduleType, int channel) {
SetName(moduleType + wpi::Twine('[') + wpi::Twine(channel) + wpi::Twine(']'));
}
/**
* Sets the name of the sensor with a module and channel number.
*
* @param moduleType A string that defines the module name in the label for
* the value
* @param moduleNumber The number of the particular module type
* @param channel The channel number the device is plugged into (usually
* PWM)
*/
void SendableBase::SetName(const wpi::Twine& moduleType, int moduleNumber,
int channel) {
SetName(moduleType + wpi::Twine('[') + wpi::Twine(moduleNumber) +

View File

@@ -13,7 +13,4 @@ const char* SendableChooserBase::kDefault = "default";
const char* SendableChooserBase::kOptions = "options";
const char* SendableChooserBase::kSelected = "selected";
/**
* Instantiates a SendableChooser.
*/
SendableChooserBase::SendableChooserBase() : SendableBase(false) {}

View File

@@ -55,103 +55,42 @@ Singleton& Singleton::GetInstance() {
void SmartDashboard::init() { Singleton::GetInstance(); }
/**
* Determines whether the given key is in this table.
*
* @param key the key to search for
* @return true if the table as a value assigned to the given key
*/
bool SmartDashboard::ContainsKey(wpi::StringRef key) {
return Singleton::GetInstance().table->ContainsKey(key);
}
/**
* @param types bitmask of types; 0 is treated as a "don't care".
* @return keys currently in the table
*/
std::vector<std::string> SmartDashboard::GetKeys(int types) {
return Singleton::GetInstance().table->GetKeys(types);
}
/**
* Makes a key's value persistent through program restarts.
*
* @param key the key to make persistent
*/
void SmartDashboard::SetPersistent(wpi::StringRef key) {
Singleton::GetInstance().table->GetEntry(key).SetPersistent();
}
/**
* Stop making a key's value persistent through program restarts.
* The key cannot be null.
*
* @param key the key name
*/
void SmartDashboard::ClearPersistent(wpi::StringRef key) {
Singleton::GetInstance().table->GetEntry(key).ClearPersistent();
}
/**
* Returns whether the value is persistent through program restarts.
* The key cannot be null.
*
* @param key the key name
*/
bool SmartDashboard::IsPersistent(wpi::StringRef key) {
return Singleton::GetInstance().table->GetEntry(key).IsPersistent();
}
/**
* Sets flags on the specified key in this table. The key can
* not be null.
*
* @param key the key name
* @param flags the flags to set (bitmask)
*/
void SmartDashboard::SetFlags(wpi::StringRef key, unsigned int flags) {
Singleton::GetInstance().table->GetEntry(key).SetFlags(flags);
}
/**
* Clears flags on the specified key in this table. The key can
* not be null.
*
* @param key the key name
* @param flags the flags to clear (bitmask)
*/
void SmartDashboard::ClearFlags(wpi::StringRef key, unsigned int flags) {
Singleton::GetInstance().table->GetEntry(key).ClearFlags(flags);
}
/**
* Returns the flags for the specified key.
*
* @param key the key name
* @return the flags, or 0 if the key is not defined
*/
unsigned int SmartDashboard::GetFlags(wpi::StringRef key) {
return Singleton::GetInstance().table->GetEntry(key).GetFlags();
}
/**
* Deletes the specified key in this table.
*
* @param key the key name
*/
void SmartDashboard::Delete(wpi::StringRef key) {
Singleton::GetInstance().table->Delete(key);
}
/**
* Maps the specified key to the specified value in this table.
*
* The value can be retrieved by calling the get method with a key that is equal
* to the original key.
*
* @param keyName the key
* @param value the value
*/
void SmartDashboard::PutData(wpi::StringRef key, Sendable* data) {
if (data == nullptr) {
wpi_setGlobalWPIErrorWithContext(NullParameter, "value");
@@ -171,15 +110,6 @@ void SmartDashboard::PutData(wpi::StringRef key, Sendable* data) {
}
}
/**
* Maps the specified key (where the key is the name of the Sendable)
* to the specified value in this table.
*
* The value can be retrieved by calling the get method with a key that is equal
* to the original key.
*
* @param value the value
*/
void SmartDashboard::PutData(Sendable* value) {
if (value == nullptr) {
wpi_setGlobalWPIErrorWithContext(NullParameter, "value");
@@ -188,12 +118,6 @@ void SmartDashboard::PutData(Sendable* value) {
PutData(value->GetName(), value);
}
/**
* Returns the value at the specified key.
*
* @param keyName the key
* @return the value
*/
Sendable* SmartDashboard::GetData(wpi::StringRef key) {
auto& inst = Singleton::GetInstance();
std::lock_guard<wpi::mutex> lock(inst.tablesToDataMutex);
@@ -205,352 +129,131 @@ Sendable* SmartDashboard::GetData(wpi::StringRef key) {
return data->getValue().sendable;
}
/**
* Maps the specified key to the specified complex value (such as an array) in
* this table.
*
* The value can be retrieved by calling the RetrieveValue method with a key
* that is equal to the original key.
*
* @param keyName the key
* @param value the value
* @return False if the table key already exists with a different type
*/
bool SmartDashboard::PutValue(wpi::StringRef keyName,
std::shared_ptr<nt::Value> value) {
return Singleton::GetInstance().table->GetEntry(keyName).SetValue(value);
}
/**
* Gets the current value in the table, setting it if it does not exist.
*
* @param key the key
* @param defaultValue The default value to set if key doesn't exist.
* @returns False if the table key exists with a different type
*/
bool SmartDashboard::SetDefaultValue(wpi::StringRef key,
std::shared_ptr<nt::Value> defaultValue) {
return Singleton::GetInstance().table->GetEntry(key).SetDefaultValue(
defaultValue);
}
/**
* Retrieves the complex value (such as an array) in this table into the complex
* data object.
*
* @param keyName the key
* @param value the object to retrieve the value into
*/
std::shared_ptr<nt::Value> SmartDashboard::GetValue(wpi::StringRef keyName) {
return Singleton::GetInstance().table->GetEntry(keyName).GetValue();
}
/**
* Maps the specified key to the specified value in this table.
*
* The value can be retrieved by calling the get method with a key that is equal
* to the original key.
*
* @param keyName the key
* @param value the value
* @return False if the table key already exists with a different type
*/
bool SmartDashboard::PutBoolean(wpi::StringRef keyName, bool value) {
return Singleton::GetInstance().table->GetEntry(keyName).SetBoolean(value);
}
/**
* Gets the current value in the table, setting it if it does not exist.
* @param key the key
* @param defaultValue the default value to set if key doesn't exist.
* @returns False if the table key exists with a different type
*/
bool SmartDashboard::SetDefaultBoolean(wpi::StringRef key, bool defaultValue) {
return Singleton::GetInstance().table->GetEntry(key).SetDefaultBoolean(
defaultValue);
}
/**
* Returns the value at the specified key.
*
* If the key is not found, returns the default value.
*
* @param keyName the key
* @return the value
*/
bool SmartDashboard::GetBoolean(wpi::StringRef keyName, bool defaultValue) {
return Singleton::GetInstance().table->GetEntry(keyName).GetBoolean(
defaultValue);
}
/**
* Maps the specified key to the specified value in this table.
*
* The value can be retrieved by calling the get method with a key that is equal
* to the original key.
*
* @param keyName the key
* @param value the value
* @return False if the table key already exists with a different type
*/
bool SmartDashboard::PutNumber(wpi::StringRef keyName, double value) {
return Singleton::GetInstance().table->GetEntry(keyName).SetDouble(value);
}
/**
* Gets the current value in the table, setting it if it does not exist.
*
* @param key The key.
* @param defaultValue The default value to set if key doesn't exist.
* @returns False if the table key exists with a different type
*/
bool SmartDashboard::SetDefaultNumber(wpi::StringRef key, double defaultValue) {
return Singleton::GetInstance().table->GetEntry(key).SetDefaultDouble(
defaultValue);
}
/**
* Returns the value at the specified key.
*
* If the key is not found, returns the default value.
*
* @param keyName the key
* @return the value
*/
double SmartDashboard::GetNumber(wpi::StringRef keyName, double defaultValue) {
return Singleton::GetInstance().table->GetEntry(keyName).GetDouble(
defaultValue);
}
/**
* Maps the specified key to the specified value in this table.
*
* The value can be retrieved by calling the get method with a key that is equal
* to the original key.
*
* @param keyName the key
* @param value the value
* @return False if the table key already exists with a different type
*/
bool SmartDashboard::PutString(wpi::StringRef keyName, wpi::StringRef value) {
return Singleton::GetInstance().table->GetEntry(keyName).SetString(value);
}
/**
* Gets the current value in the table, setting it if it does not exist.
* @param key the key
* @param defaultValue the default value to set if key doesn't exist.
* @returns False if the table key exists with a different type
*/
bool SmartDashboard::SetDefaultString(wpi::StringRef key,
wpi::StringRef defaultValue) {
return Singleton::GetInstance().table->GetEntry(key).SetDefaultString(
defaultValue);
}
/**
* Returns the value at the specified key.
*
* If the key is not found, returns the default value.
*
* @param keyName the key
* @return the value
*/
std::string SmartDashboard::GetString(wpi::StringRef keyName,
wpi::StringRef defaultValue) {
return Singleton::GetInstance().table->GetEntry(keyName).GetString(
defaultValue);
}
/**
* Put a boolean array in the table.
*
* @param key the key to be assigned to
* @param value the value that will be assigned
* @return False if the table key already exists with a different type
*
* @note The array must be of int's rather than of bool's because
* std::vector<bool> is special-cased in C++. 0 is false, any
* non-zero value is true.
*/
bool SmartDashboard::PutBooleanArray(wpi::StringRef key,
wpi::ArrayRef<int> value) {
return Singleton::GetInstance().table->GetEntry(key).SetBooleanArray(value);
}
/**
* Gets the current value in the table, setting it if it does not exist.
*
* @param key the key
* @param defaultValue the default value to set if key doesn't exist.
* @returns False if the table key exists with a different type
*/
bool SmartDashboard::SetDefaultBooleanArray(wpi::StringRef key,
wpi::ArrayRef<int> defaultValue) {
return Singleton::GetInstance().table->GetEntry(key).SetDefaultBooleanArray(
defaultValue);
}
/**
* Returns the boolean array the key maps to.
*
* If the key does not exist or is of different type, it will return the default
* value.
*
* @param key The key to look up.
* @param defaultValue The value to be returned if no value is found.
* @return the value associated with the given key or the given default value
* if there is no value associated with the key
*
* @note This makes a copy of the array. If the overhead of this is a concern,
* use GetValue() instead.
*
* @note The returned array is std::vector<int> instead of std::vector<bool>
* because std::vector<bool> is special-cased in C++. 0 is false, any
* non-zero value is true.
*/
std::vector<int> SmartDashboard::GetBooleanArray(
wpi::StringRef key, wpi::ArrayRef<int> defaultValue) {
return Singleton::GetInstance().table->GetEntry(key).GetBooleanArray(
defaultValue);
}
/**
* Put a number array in the table.
*
* @param key The key to be assigned to.
* @param value The value that will be assigned.
* @return False if the table key already exists with a different type
*/
bool SmartDashboard::PutNumberArray(wpi::StringRef key,
wpi::ArrayRef<double> value) {
return Singleton::GetInstance().table->GetEntry(key).SetDoubleArray(value);
}
/**
* Gets the current value in the table, setting it if it does not exist.
*
* @param key The key.
* @param defaultValue The default value to set if key doesn't exist.
* @returns False if the table key exists with a different type
*/
bool SmartDashboard::SetDefaultNumberArray(wpi::StringRef key,
wpi::ArrayRef<double> defaultValue) {
return Singleton::GetInstance().table->GetEntry(key).SetDefaultDoubleArray(
defaultValue);
}
/**
* Returns the number array the key maps to.
*
* If the key does not exist or is of different type, it will return the default
* value.
*
* @param key The key to look up.
* @param defaultValue The value to be returned if no value is found.
* @return the value associated with the given key or the given default value
* if there is no value associated with the key
*
* @note This makes a copy of the array. If the overhead of this is a concern,
* use GetValue() instead.
*/
std::vector<double> SmartDashboard::GetNumberArray(
wpi::StringRef key, wpi::ArrayRef<double> defaultValue) {
return Singleton::GetInstance().table->GetEntry(key).GetDoubleArray(
defaultValue);
}
/**
* Put a string array in the table.
*
* @param key The key to be assigned to.
* @param value The value that will be assigned.
* @return False if the table key already exists with a different type
*/
bool SmartDashboard::PutStringArray(wpi::StringRef key,
wpi::ArrayRef<std::string> value) {
return Singleton::GetInstance().table->GetEntry(key).SetStringArray(value);
}
/**
* Gets the current value in the table, setting it if it does not exist.
*
* @param key The key.
* @param defaultValue The default value to set if key doesn't exist.
* @returns False if the table key exists with a different type
*/
bool SmartDashboard::SetDefaultStringArray(
wpi::StringRef key, wpi::ArrayRef<std::string> defaultValue) {
return Singleton::GetInstance().table->GetEntry(key).SetDefaultStringArray(
defaultValue);
}
/**
* Returns the string array the key maps to.
*
* If the key does not exist or is of different type, it will return the default
* value.
*
* @param key The key to look up.
* @param defaultValue The value to be returned if no value is found.
* @return the value associated with the given key or the given default value
* if there is no value associated with the key
*
* @note This makes a copy of the array. If the overhead of this is a concern,
* use GetValue() instead.
*/
std::vector<std::string> SmartDashboard::GetStringArray(
wpi::StringRef key, wpi::ArrayRef<std::string> defaultValue) {
return Singleton::GetInstance().table->GetEntry(key).GetStringArray(
defaultValue);
}
/**
* Put a raw value (byte array) in the table.
*
* @param key The key to be assigned to.
* @param value The value that will be assigned.
* @return False if the table key already exists with a different type
*/
bool SmartDashboard::PutRaw(wpi::StringRef key, wpi::StringRef value) {
return Singleton::GetInstance().table->GetEntry(key).SetRaw(value);
}
/**
* Gets the current value in the table, setting it if it does not exist.
*
* @param key The key.
* @param defaultValue The default value to set if key doesn't exist.
* @returns False if the table key exists with a different type
*/
bool SmartDashboard::SetDefaultRaw(wpi::StringRef key,
wpi::StringRef defaultValue) {
return Singleton::GetInstance().table->GetEntry(key).SetDefaultRaw(
defaultValue);
}
/**
* Returns the raw value (byte array) the key maps to.
*
* If the key does not exist or is of different type, it will return the default
* value.
*
* @param key The key to look up.
* @param defaultValue The value to be returned if no value is found.
* @return the value associated with the given key or the given default value
* if there is no value associated with the key
*
* @note This makes a copy of the raw contents. If the overhead of this is a
* concern, use GetValue() instead.
*/
std::string SmartDashboard::GetRaw(wpi::StringRef key,
wpi::StringRef defaultValue) {
return Singleton::GetInstance().table->GetEntry(key).GetRaw(defaultValue);
}
/**
* Puts all sendable data to the dashboard.
*/
bool SmartDashboard::PutValue(wpi::StringRef keyName,
std::shared_ptr<nt::Value> value) {
return Singleton::GetInstance().table->GetEntry(keyName).SetValue(value);
}
bool SmartDashboard::SetDefaultValue(wpi::StringRef key,
std::shared_ptr<nt::Value> defaultValue) {
return Singleton::GetInstance().table->GetEntry(key).SetDefaultValue(
defaultValue);
}
std::shared_ptr<nt::Value> SmartDashboard::GetValue(wpi::StringRef keyName) {
return Singleton::GetInstance().table->GetEntry(keyName).GetValue();
}
void SmartDashboard::UpdateValues() {
auto& inst = Singleton::GetInstance();
std::lock_guard<wpi::mutex> lock(inst.tablesToDataMutex);

View File

@@ -17,20 +17,9 @@
using namespace frc;
/**
* Constructor using the default PCM ID (0).
*
* @param channel The channel on the PCM to control (0..7).
*/
Solenoid::Solenoid(int channel)
: Solenoid(SensorUtil::GetDefaultSolenoidModule(), channel) {}
/**
* Constructor.
*
* @param moduleNumber The CAN ID of the PCM the solenoid is attached to
* @param channel The channel on the PCM to control (0..7).
*/
Solenoid::Solenoid(int moduleNumber, int channel)
: SolenoidBase(moduleNumber), m_channel(channel) {
if (!SensorUtil::CheckSolenoidModule(m_moduleNumber)) {
@@ -59,16 +48,8 @@ Solenoid::Solenoid(int moduleNumber, int channel)
SetName("Solenoid", m_moduleNumber, m_channel);
}
/**
* Destructor.
*/
Solenoid::~Solenoid() { HAL_FreeSolenoidPort(m_solenoidHandle); }
/**
* Set the value of a solenoid.
*
* @param on Turn the solenoid output off or on.
*/
void Solenoid::Set(bool on) {
if (StatusIsFatal()) return;
int32_t status = 0;
@@ -76,11 +57,6 @@ void Solenoid::Set(bool on) {
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Read the current value of the solenoid.
*
* @return The current value of the solenoid.
*/
bool Solenoid::Get() const {
if (StatusIsFatal()) return false;
int32_t status = 0;
@@ -89,30 +65,11 @@ bool Solenoid::Get() const {
return value;
}
/**
* Check if solenoid is blacklisted.
*
* If a solenoid is shorted, it is added to the blacklist and
* disabled until power cycle, or until faults are cleared.
*
* @see ClearAllPCMStickyFaults()
*
* @return If solenoid is disabled due to short.
*/
bool Solenoid::IsBlackListed() const {
int value = GetPCMSolenoidBlackList(m_moduleNumber) & (1 << m_channel);
return (value != 0);
}
/**
* Set the pulse duration in the PCM. This is used in conjunction with
* the startPulse method to allow the PCM to control the timing of a pulse.
* The timing can be controlled in 0.01 second increments.
*
* @param durationSeconds The duration of the pulse, from 0.01 to 2.55 seconds.
*
* @see startPulse()
*/
void Solenoid::SetPulseDuration(double durationSeconds) {
int32_t durationMS = durationSeconds * 1000;
if (StatusIsFatal()) return;
@@ -121,12 +78,6 @@ void Solenoid::SetPulseDuration(double durationSeconds) {
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
}
/**
* Trigger the PCM to generate a pulse of the duration set in
* setPulseDuration.
*
* @see setPulseDuration()
*/
void Solenoid::StartPulse() {
if (StatusIsFatal()) return;
int32_t status = 0;

View File

@@ -12,19 +12,6 @@
using namespace frc;
/**
* Constructor
*
* @param moduleNumber The CAN PCM ID.
*/
SolenoidBase::SolenoidBase(int moduleNumber) : m_moduleNumber(moduleNumber) {}
/**
* Read all 8 solenoids as a single byte
*
* @param module the module to read from
* @return The current value of all 8 solenoids on the module.
*/
int SolenoidBase::GetAll(int module) {
int value = 0;
int32_t status = 0;
@@ -33,106 +20,44 @@ int SolenoidBase::GetAll(int module) {
return value;
}
/**
* Read all 8 solenoids as a single byte
*
* @return The current value of all 8 solenoids on the module.
*/
int SolenoidBase::GetAll() const {
return SolenoidBase::GetAll(m_moduleNumber);
}
/**
* Reads complete solenoid blacklist for all 8 solenoids as a single byte.
*
* If a solenoid is shorted, it is added to the blacklist and
* disabled until power cycle, or until faults are cleared.
* @see ClearAllPCMStickyFaults()
*
* @param module the module to read from
* @return The solenoid blacklist of all 8 solenoids on the module.
*/
int SolenoidBase::GetPCMSolenoidBlackList(int module) {
int32_t status = 0;
return HAL_GetPCMSolenoidBlackList(module, &status);
}
/**
* Reads complete solenoid blacklist for all 8 solenoids as a single byte.
*
* If a solenoid is shorted, it is added to the blacklist and
* disabled until power cycle, or until faults are cleared.
* @see ClearAllPCMStickyFaults()
*
* @return The solenoid blacklist of all 8 solenoids on the module.
*/
int SolenoidBase::GetPCMSolenoidBlackList() const {
return SolenoidBase::GetPCMSolenoidBlackList(m_moduleNumber);
}
/**
* @param module the module to read from
* @return true if PCM sticky fault is set : The common highside solenoid
* voltage rail is too low, most likely a solenoid channel is shorted.
*/
bool SolenoidBase::GetPCMSolenoidVoltageStickyFault(int module) {
int32_t status = 0;
return HAL_GetPCMSolenoidVoltageStickyFault(module, &status);
}
/**
* @return true if PCM sticky fault is set : The common highside solenoid
* voltage rail is too low, most likely a solenoid channel is shorted.
*/
bool SolenoidBase::GetPCMSolenoidVoltageStickyFault() const {
return SolenoidBase::GetPCMSolenoidVoltageStickyFault(m_moduleNumber);
}
/**
* @param module the module to read from
* @return true if PCM is in fault state : The common highside solenoid voltage
* rail is too low, most likely a solenoid channel is shorted.
*/
bool SolenoidBase::GetPCMSolenoidVoltageFault(int module) {
int32_t status = 0;
return HAL_GetPCMSolenoidVoltageFault(module, &status);
}
/**
* @return true if PCM is in fault state : The common highside solenoid voltage
* rail is too low, most likely a solenoid channel is shorted.
*/
bool SolenoidBase::GetPCMSolenoidVoltageFault() const {
return SolenoidBase::GetPCMSolenoidVoltageFault(m_moduleNumber);
}
/**
* Clear ALL sticky faults inside PCM that Compressor is wired to.
*
* If a sticky fault is set, then it will be persistently cleared. Compressor
* drive maybe momentarily disable while flags are being cleared. Care should
* be taken to not call this too frequently, otherwise normal compressor
* functionality may be prevented.
*
* If no sticky faults are set then this call will have no effect.
*
* @param module the module to read from
*/
void SolenoidBase::ClearAllPCMStickyFaults(int module) {
int32_t status = 0;
return HAL_ClearAllPCMStickyFaults(module, &status);
}
/**
* Clear ALL sticky faults inside PCM that Compressor is wired to.
*
* If a sticky fault is set, then it will be persistently cleared. Compressor
* drive maybe momentarily disable while flags are being cleared. Care should
* be taken to not call this too frequently, otherwise normal compressor
* functionality may be prevented.
*
* If no sticky faults are set then this call will have no effect.
*/
void SolenoidBase::ClearAllPCMStickyFaults() {
SolenoidBase::ClearAllPCMStickyFaults(m_moduleNumber);
}
SolenoidBase::SolenoidBase(int moduleNumber) : m_moduleNumber(moduleNumber) {}

View File

@@ -11,28 +11,20 @@
using namespace frc;
/**
* Note that the Spark uses the following bounds for PWM values. These values
* should work reasonably well for most controllers, but if users experience
* issues such as asymmetric behavior around the deadband or inability to
* saturate the controller in either direction, calibration is recommended.
* The calibration procedure can be found in the Spark User Manual available
* from REV Robotics.
*
* 2.003ms = full "forward"
* 1.55ms = the "high end" of the deadband range
* 1.50ms = center of the deadband range (off)
* 1.46ms = the "low end" of the deadband range
* 0.999ms = full "reverse"
*/
/**
* Constructor for a Spark.
*
* @param channel The PWM channel that the Spark is attached to. 0-9 are
* on-board, 10-19 are on the MXP port
*/
Spark::Spark(int channel) : PWMSpeedController(channel) {
/* Note that the Spark uses the following bounds for PWM values. These values
* should work reasonably well for most controllers, but if users experience
* issues such as asymmetric behavior around the deadband or inability to
* saturate the controller in either direction, calibration is recommended.
* The calibration procedure can be found in the Spark User Manual available
* from REV Robotics.
*
* 2.003ms = full "forward"
* 1.55ms = the "high end" of the deadband range
* 1.50ms = center of the deadband range (off)
* 1.46ms = the "low end" of the deadband range
* 0.999ms = full "reverse"
*/
SetBounds(2.003, 1.55, 1.50, 1.46, .999);
SetPeriodMultiplier(kPeriodMultiplier_1X);
SetSpeed(0.0);

View File

@@ -9,36 +9,14 @@
using namespace frc;
/**
* Allocate a PID object with the given constants for P, I, and D.
*
* @param Kp the proportional coefficient
* @param Ki the integral coefficient
* @param Kd the derivative coefficient
* @param source The PIDSource object that is used to get values
* @param output The PIDOutput object that is set to the output percentage
*/
SynchronousPID::SynchronousPID(double Kp, double Ki, double Kd,
PIDSource& source, PIDOutput& output)
: SynchronousPID(Kp, Ki, Kd, 0.0, source, output) {}
/**
* Allocate a PID object with the given constants for P, I, and D.
*
* @param Kp the proportional coefficient
* @param Ki the integral coefficient
* @param Kd the derivative coefficient
* @param Kf the feed forward term
* @param source The PIDSource object that is used to get values
* @param output The PIDOutput object that is set to the output percentage
*/
SynchronousPID::SynchronousPID(double Kp, double Ki, double Kd, double Kf,
PIDSource& source, PIDOutput& output)
: PIDBase(Kp, Ki, Kd, Kf, source, output) {
m_enabled = true;
}
/**
* Read the input, calculate the output accordingly, and write to the output.
*/
void SynchronousPID::Calculate() { PIDBase::Calculate(); }

View File

@@ -11,12 +11,6 @@
using namespace frc;
/**
* Constructor for a Talon (original or Talon SR).
*
* @param channel The PWM channel number that the Talon is attached to. 0-9 are
* on-board, 10-19 are on the MXP port
*/
Talon::Talon(int channel) : PWMSpeedController(channel) {
/* Note that the Talon uses the following bounds for PWM values. These values
* should work reasonably well for most controllers, but if users experience

View File

@@ -12,14 +12,8 @@
#include "ErrorBase.h"
namespace frc {
/**
* Get the thread priority for the specified thread.
*
* @param thread Reference to the thread to get the priority for.
* @param isRealTime Set to true if thread is realtime, otherwise false.
* @return The current thread priority. Scaled 1-99, with 1 being highest.
*/
using namespace frc;
int GetThreadPriority(std::thread& thread, bool* isRealTime) {
int32_t status = 0;
HAL_Bool rt = false;
@@ -30,12 +24,6 @@ int GetThreadPriority(std::thread& thread, bool* isRealTime) {
return ret;
}
/**
* Get the thread priority for the current thread
*
* @param isRealTime Set to true if thread is realtime, otherwise false.
* @return The current thread priority. Scaled 1-99.
*/
int GetCurrentThreadPriority(bool* isRealTime) {
int32_t status = 0;
HAL_Bool rt = false;
@@ -45,18 +33,6 @@ int GetCurrentThreadPriority(bool* isRealTime) {
return ret;
}
/**
* Sets the thread priority for the specified thread
*
* @param thread Reference to the thread to set the priority of.
* @param realTime Set to true to set a realtime priority, false for standard
* priority.
* @param priority Priority to set the thread to. Scaled 1-99, with 1 being
* highest. On RoboRIO, priority is ignored for non realtime
* setting.
*
* @return The success state of setting the priority
*/
bool SetThreadPriority(std::thread& thread, bool realTime, int priority) {
int32_t status = 0;
auto native = thread.native_handle();
@@ -65,21 +41,9 @@ bool SetThreadPriority(std::thread& thread, bool realTime, int priority) {
return ret;
}
/**
* Sets the thread priority for the current thread
*
* @param realTime Set to true to set a realtime priority, false for standard
* priority.
* @param priority Priority to set the thread to. Scaled 1-99, with 1 being
* highest. On RoboRIO, priority is ignored for non realtime
* setting.
*
* @return The success state of setting the priority
*/
bool SetCurrentThreadPriority(bool realTime, int priority) {
int32_t status = 0;
auto ret = HAL_SetCurrentThreadPriority(realTime, priority, &status);
wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
return ret;
}
} // namespace frc

View File

@@ -17,9 +17,6 @@
using namespace frc;
/**
* Provide an alternate "main loop" via StartCompetition().
*/
void TimedRobot::StartCompetition() {
RobotInit();
@@ -46,15 +43,6 @@ void TimedRobot::StartCompetition() {
}
}
/**
* Set time period between calls to Periodic() functions.
*
* A timer event is queued for periodic event notification. Each time the
* interrupt occurs, the event will be immediately requeued for the same time
* interval.
*
* @param period Period in seconds.
*/
void TimedRobot::SetPeriod(double period) {
m_period = period;
@@ -64,9 +52,6 @@ void TimedRobot::SetPeriod(double period) {
}
}
/**
* Get time period between calls to Periodic() functions.
*/
double TimedRobot::GetPeriod() const { return m_period; }
TimedRobot::TimedRobot() {
@@ -89,9 +74,6 @@ TimedRobot::~TimedRobot() {
HAL_CleanNotifier(m_notifier, &status);
}
/**
* Update the HAL alarm time.
*/
void TimedRobot::UpdateAlarm() {
int32_t status = 0;
HAL_UpdateNotifierAlarm(

View File

@@ -17,34 +17,12 @@
namespace frc {
/**
* Pause the task for a specified time.
*
* Pause the execution of the program for a specified period of time given in
* seconds. Motors will continue to run at their last assigned values, and
* sensors will continue to update. Only the task containing the wait will pause
* until the wait time is expired.
*
* @param seconds Length of time to pause, in seconds.
*/
void Wait(double seconds) {
std::this_thread::sleep_for(std::chrono::duration<double>(seconds));
}
/**
* Return the FPGA system clock time in seconds.
*
* This is deprecated and just forwards to Timer::GetFPGATimestamp().
*
* @return Robot running time in seconds.
*/
double GetClock() { return Timer::GetFPGATimestamp(); }
/**
* @brief Gives real-time clock system time with nanosecond resolution
* @return The time, just in case you want the robot to start autonomous at 8pm
* on Saturday.
*/
double GetTime() {
using std::chrono::duration;
using std::chrono::duration_cast;
@@ -60,21 +38,9 @@ using namespace frc;
// for compatibility with msvc12--see C2864
const double Timer::kRolloverTime = (1ll << 32) / 1e6;
/**
* Create a new timer object.
*
* Create a new timer object and reset the time to zero. The timer is initially
* not running and must be started.
*/
Timer::Timer() { Reset(); }
/**
* Get the current time from the timer. If the clock is running it is derived
* from the current system clock the start time stored in the timer class. If
* the clock is not running, then return the time when it was last stopped.
*
* @return Current time value for this timer in seconds
*/
double Timer::Get() const {
double result;
double currentTime = GetFPGATimestamp();
@@ -96,24 +62,12 @@ double Timer::Get() const {
return result;
}
/**
* Reset the timer by setting the time to 0.
*
* Make the timer startTime the current time so new requests will be relative to
* now.
*/
void Timer::Reset() {
std::lock_guard<wpi::mutex> lock(m_mutex);
m_accumulatedTime = 0;
m_startTime = GetFPGATimestamp();
}
/**
* Start the timer running.
*
* Just set the running flag to true indicating that all time requests should be
* relative to the system clock.
*/
void Timer::Start() {
std::lock_guard<wpi::mutex> lock(m_mutex);
if (!m_running) {
@@ -122,13 +76,6 @@ void Timer::Start() {
}
}
/**
* Stop the timer.
*
* This computes the time as of now and clears the running flag, causing all
* subsequent time requests to be read from the accumulated time rather than
* looking at the system clock.
*/
void Timer::Stop() {
double temp = Get();
@@ -139,14 +86,6 @@ void Timer::Stop() {
}
}
/**
* Check if the period specified has passed and if it has, advance the start
* time by that period. This is useful to decide if it's time to do periodic
* work without drifting later by the time it took to get around to checking.
*
* @param period The period to check for (in seconds).
* @return True if the period has passed.
*/
bool Timer::HasPeriodPassed(double period) {
if (Get() > period) {
std::lock_guard<wpi::mutex> lock(m_mutex);
@@ -158,34 +97,11 @@ bool Timer::HasPeriodPassed(double period) {
return false;
}
/**
* Return the FPGA system clock time in seconds.
*
* Return the time from the FPGA hardware clock in seconds since the FPGA
* started. Rolls over after 71 minutes.
*
* @returns Robot running time in seconds.
*/
double Timer::GetFPGATimestamp() {
// FPGA returns the timestamp in microseconds
return RobotController::GetFPGATime() * 1.0e-6;
}
/**
* Return the approximate match time.
*
* The FMS does not send an official match time to the robots, but does send an
* approximate match time. The value will count down the time remaining in the
* current period (auto or teleop).
*
* Warning: This is not an official time (so it cannot be used to dispute ref
* calls or guarantee that a function will trigger before the match ends).
*
* The Practice Match function of the DS approximates the behaviour seen on the
* field.
*
* @return Time remaining in current match period (auto or teleop)
*/
double Timer::GetMatchTime() {
return DriverStation::GetInstance().GetMatchTime();
}

View File

@@ -25,68 +25,6 @@ std::atomic<bool> Ultrasonic::m_automaticEnabled{false};
std::vector<Ultrasonic*> Ultrasonic::m_sensors;
std::thread Ultrasonic::m_thread;
/**
* Background task that goes through the list of ultrasonic sensors and pings
* each one in turn. The counter is configured to read the timing of the
* returned echo pulse.
*
* DANGER WILL ROBINSON, DANGER WILL ROBINSON:
* This code runs as a task and assumes that none of the ultrasonic sensors
* will change while it's running. Make sure to disable automatic mode before
* touching the list.
*/
void Ultrasonic::UltrasonicChecker() {
while (m_automaticEnabled) {
for (auto& sensor : m_sensors) {
if (!m_automaticEnabled) break;
if (sensor->IsEnabled()) {
sensor->m_pingChannel->Pulse(kPingTime); // do the ping
}
Wait(0.1); // wait for ping to return
}
}
}
/**
* Initialize the Ultrasonic Sensor.
*
* This is the common code that initializes the ultrasonic sensor given that
* there are two digital I/O channels allocated. If the system was running in
* automatic mode (round robin) when the new sensor is added, it is stopped, the
* sensor is added, then automatic mode is restored.
*/
void Ultrasonic::Initialize() {
bool originalMode = m_automaticEnabled;
SetAutomaticMode(false); // Kill task when adding a new sensor
// Link this instance on the list
m_sensors.emplace_back(this);
m_counter.SetMaxPeriod(1.0);
m_counter.SetSemiPeriodMode(true);
m_counter.Reset();
m_enabled = true; // Make it available for round robin scheduling
SetAutomaticMode(originalMode);
static int instances = 0;
instances++;
HAL_Report(HALUsageReporting::kResourceType_Ultrasonic, instances);
SetName("Ultrasonic", m_echoChannel->GetChannel());
}
/**
* Create an instance of the Ultrasonic Sensor.
*
* This is designed to support the Daventech SRF04 and Vex ultrasonic sensors.
*
* @param pingChannel The digital output channel that sends the pulse to
* initiate the sensor sending the ping.
* @param echoChannel The digital input channel that receives the echo. The
* length of time that the echo is high represents the
* round trip time of the ping, and the distance.
* @param units The units returned in either kInches or kMilliMeters
*/
Ultrasonic::Ultrasonic(int pingChannel, int echoChannel, DistanceUnit units)
: m_pingChannel(std::make_shared<DigitalOutput>(pingChannel)),
m_echoChannel(std::make_shared<DigitalInput>(echoChannel)),
@@ -97,16 +35,6 @@ Ultrasonic::Ultrasonic(int pingChannel, int echoChannel, DistanceUnit units)
AddChild(m_echoChannel);
}
/**
* Create an instance of an Ultrasonic Sensor from a DigitalInput for the echo
* channel and a DigitalOutput for the ping channel.
*
* @param pingChannel The digital output object that starts the sensor doing a
* ping. Requires a 10uS pulse to start.
* @param echoChannel The digital input object that times the return pulse to
* determine the range.
* @param units The units returned in either kInches or kMilliMeters
*/
Ultrasonic::Ultrasonic(DigitalOutput* pingChannel, DigitalInput* echoChannel,
DistanceUnit units)
: m_pingChannel(pingChannel, NullDeleter<DigitalOutput>()),
@@ -121,16 +49,6 @@ Ultrasonic::Ultrasonic(DigitalOutput* pingChannel, DigitalInput* echoChannel,
Initialize();
}
/**
* Create an instance of an Ultrasonic Sensor from a DigitalInput for the echo
* channel and a DigitalOutput for the ping channel.
*
* @param pingChannel The digital output object that starts the sensor doing a
* ping. Requires a 10uS pulse to start.
* @param echoChannel The digital input object that times the return pulse to
* determine the range.
* @param units The units returned in either kInches or kMilliMeters
*/
Ultrasonic::Ultrasonic(DigitalOutput& pingChannel, DigitalInput& echoChannel,
DistanceUnit units)
: m_pingChannel(&pingChannel, NullDeleter<DigitalOutput>()),
@@ -140,16 +58,6 @@ Ultrasonic::Ultrasonic(DigitalOutput& pingChannel, DigitalInput& echoChannel,
Initialize();
}
/**
* Create an instance of an Ultrasonic Sensor from a DigitalInput for the echo
* channel and a DigitalOutput for the ping channel.
*
* @param pingChannel The digital output object that starts the sensor doing a
* ping. Requires a 10uS pulse to start.
* @param echoChannel The digital input object that times the return pulse to
* determine the range.
* @param units The units returned in either kInches or kMilliMeters
*/
Ultrasonic::Ultrasonic(std::shared_ptr<DigitalOutput> pingChannel,
std::shared_ptr<DigitalInput> echoChannel,
DistanceUnit units)
@@ -160,15 +68,12 @@ Ultrasonic::Ultrasonic(std::shared_ptr<DigitalOutput> pingChannel,
Initialize();
}
/**
* Destructor for the ultrasonic sensor.
*
* Delete the instance of the ultrasonic sensor by freeing the allocated digital
* channels. If the system was in automatic mode (round robin), then it is
* stopped, then started again after this sensor is removed (provided this
* wasn't the last sensor).
*/
Ultrasonic::~Ultrasonic() {
// Delete the instance of the ultrasonic sensor by freeing the allocated
// digital channels. If the system was in automatic mode (round robin), then
// it is stopped, then started again after this sensor is removed (provided
// this wasn't the last sensor).
bool wasAutomaticMode = m_automaticEnabled;
SetAutomaticMode(false);
@@ -181,19 +86,18 @@ Ultrasonic::~Ultrasonic() {
}
}
/**
* Turn Automatic mode on/off.
*
* When in Automatic mode, all sensors will fire in round robin, waiting a set
* time between each sensor.
*
* @param enabling Set to true if round robin scheduling should start for all
* the ultrasonic sensors. This scheduling method assures that
* the sensors are non-interfering because no two sensors fire
* at the same time. If another scheduling algorithm is
* prefered, it can be implemented by pinging the sensors
* manually and waiting for the results to come back.
*/
void Ultrasonic::Ping() {
wpi_assert(!m_automaticEnabled);
// Reset the counter to zero (invalid data now)
m_counter.Reset();
// Do the ping to start getting a single range
m_pingChannel->Pulse(kPingTime);
}
bool Ultrasonic::IsRangeValid() const { return m_counter.Get() > 1; }
void Ultrasonic::SetAutomaticMode(bool enabling) {
if (enabling == m_automaticEnabled) return; // ignore the case of no change
@@ -226,40 +130,6 @@ void Ultrasonic::SetAutomaticMode(bool enabling) {
}
}
/**
* Single ping to ultrasonic sensor.
*
* Send out a single ping to the ultrasonic sensor. This only works if automatic
* (round robin) mode is disabled. A single ping is sent out, and the counter
* should count the semi-period when it comes in. The counter is reset to make
* the current value invalid.
*/
void Ultrasonic::Ping() {
wpi_assert(!m_automaticEnabled);
// Reset the counter to zero (invalid data now)
m_counter.Reset();
// Do the ping to start getting a single range
m_pingChannel->Pulse(kPingTime);
}
/**
* Check if there is a valid range measurement.
*
* The ranges are accumulated in a counter that will increment on each edge of
* the echo (return) signal. If the count is not at least 2, then the range has
* not yet been measured, and is invalid.
*/
bool Ultrasonic::IsRangeValid() const { return m_counter.Get() > 1; }
/**
* Get the range in inches from the ultrasonic sensor.
*
* @return Range in inches of the target returned from the ultrasonic sensor. If
* there is no valid value yet, i.e. at least one measurement hasn't
* completed, then return 0.
*/
double Ultrasonic::GetRangeInches() const {
if (IsRangeValid())
return m_counter.GetPeriod() * kSpeedOfSoundInchesPerSec / 2.0;
@@ -267,20 +137,18 @@ double Ultrasonic::GetRangeInches() const {
return 0;
}
/**
* Get the range in millimeters from the ultrasonic sensor.
*
* @return Range in millimeters of the target returned by the ultrasonic sensor.
* If there is no valid value yet, i.e. at least one measurement hasn't
* completed, then return 0.
*/
double Ultrasonic::GetRangeMM() const { return GetRangeInches() * 25.4; }
/**
* Get the range in the current DistanceUnit for the PIDSource base object.
*
* @return The range in DistanceUnit
*/
bool Ultrasonic::IsEnabled() const { return m_enabled; }
void Ultrasonic::SetEnabled(bool enable) { m_enabled = enable; }
void Ultrasonic::SetDistanceUnits(DistanceUnit units) { m_units = units; }
Ultrasonic::DistanceUnit Ultrasonic::GetDistanceUnits() const {
return m_units;
}
double Ultrasonic::PIDGet() {
switch (m_units) {
case Ultrasonic::kInches:
@@ -298,25 +166,40 @@ void Ultrasonic::SetPIDSourceType(PIDSourceType pidSource) {
}
}
/**
* Set the current DistanceUnit that should be used for the PIDSource base
* object.
*
* @param units The DistanceUnit that should be used.
*/
void Ultrasonic::SetDistanceUnits(DistanceUnit units) { m_units = units; }
/**
* Get the current DistanceUnit that is used for the PIDSource base object.
*
* @return The type of DistanceUnit that is being used.
*/
Ultrasonic::DistanceUnit Ultrasonic::GetDistanceUnits() const {
return m_units;
}
void Ultrasonic::InitSendable(SendableBuilder& builder) {
builder.SetSmartDashboardType("Ultrasonic");
builder.AddDoubleProperty("Value", [=]() { return GetRangeInches(); },
nullptr);
}
void Ultrasonic::Initialize() {
bool originalMode = m_automaticEnabled;
SetAutomaticMode(false); // Kill task when adding a new sensor
// Link this instance on the list
m_sensors.emplace_back(this);
m_counter.SetMaxPeriod(1.0);
m_counter.SetSemiPeriodMode(true);
m_counter.Reset();
m_enabled = true; // Make it available for round robin scheduling
SetAutomaticMode(originalMode);
static int instances = 0;
instances++;
HAL_Report(HALUsageReporting::kResourceType_Ultrasonic, instances);
SetName("Ultrasonic", m_echoChannel->GetChannel());
}
void Ultrasonic::UltrasonicChecker() {
while (m_automaticEnabled) {
for (auto& sensor : m_sensors) {
if (!m_automaticEnabled) break;
if (sensor->IsEnabled()) {
sensor->m_pingChannel->Pulse(kPingTime); // do the ping
}
Wait(0.1); // wait for ping to return
}
}
}

View File

@@ -26,12 +26,6 @@
using namespace frc;
/**
* Assert implementation.
*
* This allows breakpoints to be set on an assert. The users don't call this,
* but instead use the wpi_assert macros in Utility.h.
*/
bool wpi_assert_impl(bool conditionValue, const wpi::Twine& conditionText,
const wpi::Twine& message, wpi::StringRef fileName,
int lineNumber, wpi::StringRef funcName) {
@@ -98,13 +92,6 @@ void wpi_assertEqual_common_impl(const wpi::Twine& valueA,
HAL_SendError(1, 1, 0, errorBuf.c_str(), locBuf.c_str(), trace.c_str(), 1);
}
/**
* Assert equal implementation.
*
* This determines whether the two given integers are equal. If not, the value
* of each is printed along with an optional message string. The users don't
* call this, but instead use the wpi_assertEqual macros in Utility.h.
*/
bool wpi_assertEqual_impl(int valueA, int valueB,
const wpi::Twine& valueAString,
const wpi::Twine& valueBString,
@@ -117,13 +104,6 @@ bool wpi_assertEqual_impl(int valueA, int valueB,
return valueA == valueB;
}
/**
* Assert not equal implementation.
*
* This determines whether the two given integers are equal. If so, the value of
* each is printed along with an optional message string. The users don't call
* this, but instead use the wpi_assertNotEqual macros in Utility.h.
*/
bool wpi_assertNotEqual_impl(int valueA, int valueB,
const wpi::Twine& valueAString,
const wpi::Twine& valueBString,
@@ -138,14 +118,6 @@ bool wpi_assertNotEqual_impl(int valueA, int valueB,
namespace frc {
/**
* Return the FPGA Version number.
*
* For now, expect this to be competition year.
*
* @return FPGA Version number.
* @deprecated Use RobotController static class method
*/
int GetFPGAVersion() {
int32_t status = 0;
int version = HAL_GetFPGAVersion(&status);
@@ -153,16 +125,6 @@ int GetFPGAVersion() {
return version;
}
/**
* Return the FPGA Revision number.
*
* The format of the revision is 3 numbers. The 12 most significant bits are the
* Major Revision. The next 8 bits are the Minor Revision. The 12 least
* significant bits are the Build Number.
*
* @return FPGA Revision number.
* @deprecated Use RobotController static class method
*/
int64_t GetFPGARevision() {
int32_t status = 0;
int64_t revision = HAL_GetFPGARevision(&status);
@@ -170,13 +132,6 @@ int64_t GetFPGARevision() {
return revision;
}
/**
* Read the microsecond-resolution timer on the FPGA.
*
* @return The current time in microseconds according to the FPGA (since FPGA
* reset).
* @deprecated Use RobotController static class method
*/
uint64_t GetFPGATime() {
int32_t status = 0;
uint64_t time = HAL_GetFPGATime(&status);
@@ -184,12 +139,6 @@ uint64_t GetFPGATime() {
return time;
}
/**
* Get the state of the "USER" button on the roboRIO.
*
* @return True if the button is currently pressed down
* @deprecated Use RobotController static class method
*/
bool GetUserButton() {
int32_t status = 0;
@@ -224,11 +173,6 @@ static std::string demangle(char const* mangledSymbol) {
return mangledSymbol;
}
/**
* Get a stack trace, ignoring the first "offset" symbols.
*
* @param offset The number of symbols at the top of the stack to ignore
*/
std::string GetStackTrace(int offset) {
void* stackTrace[128];
int stackSize = backtrace(stackTrace, 128);

View File

@@ -11,12 +11,6 @@
using namespace frc;
/**
* Constructor for a Victor.
*
* @param channel The PWM channel number that the Victor is attached to. 0-9
* are on-board, 10-19 are on the MXP port
*/
Victor::Victor(int channel) : PWMSpeedController(channel) {
/* Note that the Victor uses the following bounds for PWM values. These
* values were determined empirically and optimized for the Victor 888. These

View File

@@ -11,15 +11,8 @@
using namespace frc;
/**
* Constructor for a VictorSP.
*
* @param channel The PWM channel that the VictorSP is attached to. 0-9 are
* on-board, 10-19 are on the MXP port
*/
VictorSP::VictorSP(int channel) : PWMSpeedController(channel) {
/**
* Note that the VictorSP uses the following bounds for PWM values. These
/* Note that the VictorSP uses the following bounds for PWM values. These
* values should work reasonably well for most controllers, but if users
* experience issues such as asymmetric behavior around the deadband or
* inability to saturate the controller in either direction, calibration is

View File

@@ -11,24 +11,11 @@
using namespace frc;
/**
* Construct an instance of an Xbox controller.
*
* The controller index is the USB port on the Driver Station.
*
* @param port The port on the Driver Station that the controller is plugged
* into (0-5).
*/
XboxController::XboxController(int port) : GenericHID(port) {
// HAL_Report(HALUsageReporting::kResourceType_XboxController, port);
HAL_Report(HALUsageReporting::kResourceType_Joystick, port);
}
/**
* Get the X axis value of the controller.
*
* @param hand Side of controller whose value should be returned.
*/
double XboxController::GetX(JoystickHand hand) const {
if (hand == kLeftHand) {
return GetRawAxis(0);
@@ -37,11 +24,6 @@ double XboxController::GetX(JoystickHand hand) const {
}
}
/**
* Get the Y axis value of the controller.
*
* @param hand Side of controller whose value should be returned.
*/
double XboxController::GetY(JoystickHand hand) const {
if (hand == kLeftHand) {
return GetRawAxis(1);
@@ -50,11 +32,6 @@ double XboxController::GetY(JoystickHand hand) const {
}
}
/**
* Get the trigger axis value of the controller.
*
* @param hand Side of controller whose value should be returned.
*/
double XboxController::GetTriggerAxis(JoystickHand hand) const {
if (hand == kLeftHand) {
return GetRawAxis(2);
@@ -63,11 +40,6 @@ double XboxController::GetTriggerAxis(JoystickHand hand) const {
}
}
/**
* Read the value of the bumper button on the controller.
*
* @param hand Side of controller whose value should be returned.
*/
bool XboxController::GetBumper(JoystickHand hand) const {
if (hand == kLeftHand) {
return GetRawButton(static_cast<int>(Button::kBumperLeft));
@@ -76,12 +48,6 @@ bool XboxController::GetBumper(JoystickHand hand) const {
}
}
/**
* Whether the bumper was pressed since the last check.
*
* @param hand Side of controller whose value should be returned.
* @return Whether the button was pressed since the last check.
*/
bool XboxController::GetBumperPressed(JoystickHand hand) {
if (hand == kLeftHand) {
return GetRawButtonPressed(static_cast<int>(Button::kBumperLeft));
@@ -90,12 +56,6 @@ bool XboxController::GetBumperPressed(JoystickHand hand) {
}
}
/**
* Whether the bumper was released since the last check.
*
* @param hand Side of controller whose value should be returned.
* @return Whether the button was released since the last check.
*/
bool XboxController::GetBumperReleased(JoystickHand hand) {
if (hand == kLeftHand) {
return GetRawButtonReleased(static_cast<int>(Button::kBumperLeft));
@@ -104,12 +64,6 @@ bool XboxController::GetBumperReleased(JoystickHand hand) {
}
}
/**
* Read the value of the stick button on the controller.
*
* @param hand Side of controller whose value should be returned.
* @return The state of the button.
*/
bool XboxController::GetStickButton(JoystickHand hand) const {
if (hand == kLeftHand) {
return GetRawButton(static_cast<int>(Button::kStickLeft));
@@ -118,12 +72,6 @@ bool XboxController::GetStickButton(JoystickHand hand) const {
}
}
/**
* Whether the stick button was pressed since the last check.
*
* @param hand Side of controller whose value should be returned.
* @return Whether the button was pressed since the last check.
*/
bool XboxController::GetStickButtonPressed(JoystickHand hand) {
if (hand == kLeftHand) {
return GetRawButtonPressed(static_cast<int>(Button::kStickLeft));
@@ -132,12 +80,6 @@ bool XboxController::GetStickButtonPressed(JoystickHand hand) {
}
}
/**
* Whether the stick button was released since the last check.
*
* @param hand Side of controller whose value should be returned.
* @return Whether the button was released since the last check.
*/
bool XboxController::GetStickButtonReleased(JoystickHand hand) {
if (hand == kLeftHand) {
return GetRawButtonReleased(static_cast<int>(Button::kStickLeft));
@@ -146,166 +88,74 @@ bool XboxController::GetStickButtonReleased(JoystickHand hand) {
}
}
/**
* Read the value of the A button on the controller.
*
* @return The state of the button.
*/
bool XboxController::GetAButton() const {
return GetRawButton(static_cast<int>(Button::kA));
}
/**
* Whether the A button was pressed since the last check.
*
* @return Whether the button was pressed since the last check.
*/
bool XboxController::GetAButtonPressed() {
return GetRawButtonPressed(static_cast<int>(Button::kA));
}
/**
* Whether the A button was released since the last check.
*
* @return Whether the button was released since the last check.
*/
bool XboxController::GetAButtonReleased() {
return GetRawButtonReleased(static_cast<int>(Button::kA));
}
/**
* Read the value of the B button on the controller.
*
* @return The state of the button.
*/
bool XboxController::GetBButton() const {
return GetRawButton(static_cast<int>(Button::kB));
}
/**
* Whether the B button was pressed since the last check.
*
* @return Whether the button was pressed since the last check.
*/
bool XboxController::GetBButtonPressed() {
return GetRawButtonPressed(static_cast<int>(Button::kB));
}
/**
* Whether the B button was released since the last check.
*
* @return Whether the button was released since the last check.
*/
bool XboxController::GetBButtonReleased() {
return GetRawButtonReleased(static_cast<int>(Button::kB));
}
/**
* Read the value of the X button on the controller.
*
* @return The state of the button.
*/
bool XboxController::GetXButton() const {
return GetRawButton(static_cast<int>(Button::kX));
}
/**
* Whether the X button was pressed since the last check.
*
* @return Whether the button was pressed since the last check.
*/
bool XboxController::GetXButtonPressed() {
return GetRawButtonPressed(static_cast<int>(Button::kX));
}
/**
* Whether the X button was released since the last check.
*
* @return Whether the button was released since the last check.
*/
bool XboxController::GetXButtonReleased() {
return GetRawButtonReleased(static_cast<int>(Button::kX));
}
/**
* Read the value of the Y button on the controller.
*
* @return The state of the button.
*/
bool XboxController::GetYButton() const {
return GetRawButton(static_cast<int>(Button::kY));
}
/**
* Whether the Y button was pressed since the last check.
*
* @return Whether the button was pressed since the last check.
*/
bool XboxController::GetYButtonPressed() {
return GetRawButtonPressed(static_cast<int>(Button::kY));
}
/**
* Whether the Y button was released since the last check.
*
* @return Whether the button was released since the last check.
*/
bool XboxController::GetYButtonReleased() {
return GetRawButtonReleased(static_cast<int>(Button::kY));
}
/**
* Read the value of the back button on the controller.
*
* @param hand Side of controller whose value should be returned.
* @return The state of the button.
*/
bool XboxController::GetBackButton() const {
return GetRawButton(static_cast<int>(Button::kBack));
}
/**
* Whether the back button was pressed since the last check.
*
* @return Whether the button was pressed since the last check.
*/
bool XboxController::GetBackButtonPressed() {
return GetRawButtonPressed(static_cast<int>(Button::kBack));
}
/**
* Whether the back button was released since the last check.
*
* @return Whether the button was released since the last check.
*/
bool XboxController::GetBackButtonReleased() {
return GetRawButtonReleased(static_cast<int>(Button::kBack));
}
/**
* Read the value of the start button on the controller.
*
* @param hand Side of controller whose value should be returned.
* @return The state of the button.
*/
bool XboxController::GetStartButton() const {
return GetRawButton(static_cast<int>(Button::kStart));
}
/**
* Whether the start button was pressed since the last check.
*
* @return Whether the button was pressed since the last check.
*/
bool XboxController::GetStartButtonPressed() {
return GetRawButtonPressed(static_cast<int>(Button::kStart));
}
/**
* Whether the start button was released since the last check.
*
* @return Whether the button was released since the last check.
*/
bool XboxController::GetStartButtonReleased() {
return GetRawButtonReleased(static_cast<int>(Button::kStart));
}