SCRIPT: wpiformat

This commit is contained in:
PJ Reiniger
2025-11-07 20:01:58 -05:00
committed by Peter Johnson
parent ae6bdc9d25
commit 2109161534
749 changed files with 5504 additions and 3936 deletions

View File

@@ -44,7 +44,7 @@ class ExpansionHub::DataStore {
std::shared_ptr<ExpansionHub::DataStore> ExpansionHub::GetForUsbId(int usbId) {
WPILIB_AssertMessage(usbId >= 0 && usbId < NumUsbPorts, "USB {} out of range",
usbId);
usbId);
std::scoped_lock lock{m_handleLock};
std::weak_ptr<DataStore>& weakStore = m_storeMap[usbId];
auto strongStore = weakStore.lock();

View File

@@ -21,10 +21,11 @@ ExpansionHubMotor::ExpansionHubMotor(int usbId, int channel)
m_velocityPidConstants{usbId, channel, true},
m_positionPidConstants{usbId, channel, false} {
WPILIB_AssertMessage(channel >= 0 && channel < ExpansionHub::NumMotorPorts,
"ExHub Motor Channel {} out of range", channel);
"ExHub Motor Channel {} out of range", channel);
if (!m_hub.CheckAndReserveMotor(channel)) {
throw WPILIB_MakeError(err::ResourceAlreadyAllocated, "Channel {}", channel);
throw WPILIB_MakeError(err::ResourceAlreadyAllocated, "Channel {}",
channel);
}
m_hub.ReportUsage(fmt::format("ExHubServo[{}]", channel), "ExHubServo");
@@ -154,7 +155,7 @@ ExpansionHubPidConstants& ExpansionHubMotor::GetPositionPidConstants() {
void ExpansionHubMotor::Follow(const ExpansionHubMotor& leader) {
if (m_hub.GetUsbId() != leader.m_hub.GetUsbId()) {
throw WPILIB_MakeError(err::InvalidParameter,
"Cannot follow motor on different hub");
"Cannot follow motor on different hub");
}
m_modePublisher.Set(kFollowerMode);
m_setpointPublisher.Set(leader.m_channel);

View File

@@ -12,10 +12,11 @@ using namespace wpi;
ExpansionHubServo::ExpansionHubServo(int usbId, int channel)
: m_hub{usbId}, m_channel{channel} {
WPILIB_AssertMessage(channel >= 0 && channel < ExpansionHub::NumServoPorts,
"ExHub Servo Channel {} out of range", channel);
"ExHub Servo Channel {} out of range", channel);
if (!m_hub.CheckAndReserveServo(channel)) {
throw WPILIB_MakeError(err::ResourceAlreadyAllocated, "Channel {}", channel);
throw WPILIB_MakeError(err::ResourceAlreadyAllocated, "Channel {}",
channel);
}
m_hub.ReportUsage(fmt::format("ExHubServo[{}]", channel), "ExHubServo");
@@ -98,7 +99,7 @@ void ExpansionHubServo::SetPWMRange(wpi::units::microsecond_t minPwm,
wpi::units::microsecond_t maxPwm) {
if (maxPwm <= minPwm) {
throw WPILIB_MakeError(err::ParameterOutOfRange,
"Max PWM must be greater than Min PWM");
"Max PWM must be greater than Min PWM");
}
m_minPwm = minPwm;
m_maxPwm = maxPwm;
@@ -110,7 +111,7 @@ void ExpansionHubServo::SetAngleRange(wpi::units::degree_t minAngle,
wpi::units::degree_t maxAngle) {
if (maxAngle <= minAngle) {
throw WPILIB_MakeError(err::ParameterOutOfRange,
"Max angle must be greater than Min angle");
"Max angle must be greater than Min angle");
}
m_minServoAngle = minAngle;
m_maxServoAngle = maxAngle;

View File

@@ -69,7 +69,8 @@ wpi::units::turns_per_second_t Tachometer::GetRevolutionsPerSecond() const {
return wpi::units::turns_per_second_t{rotationHz.value()};
}
wpi::units::revolutions_per_minute_t Tachometer::GetRevolutionsPerMinute() const {
wpi::units::revolutions_per_minute_t Tachometer::GetRevolutionsPerMinute()
const {
return wpi::units::revolutions_per_minute_t{GetRevolutionsPerSecond()};
}

View File

@@ -49,7 +49,8 @@ MecanumDrive::MecanumDrive(std::function<void(double)> frontLeftMotor,
}
void MecanumDrive::DriveCartesian(double xSpeed, double ySpeed,
double zRotation, wpi::math::Rotation2d gyroAngle) {
double zRotation,
wpi::math::Rotation2d gyroAngle) {
if (!reported) {
HAL_ReportUsage("RobotDrive", "MecanumCartesian");
reported = true;
@@ -99,17 +100,17 @@ void MecanumDrive::StopMotor() {
Feed();
}
MecanumDrive::WheelSpeeds MecanumDrive::DriveCartesianIK(double xSpeed,
double ySpeed,
double zRotation,
wpi::math::Rotation2d gyroAngle) {
MecanumDrive::WheelSpeeds MecanumDrive::DriveCartesianIK(
double xSpeed, double ySpeed, double zRotation,
wpi::math::Rotation2d gyroAngle) {
xSpeed = std::clamp(xSpeed, -1.0, 1.0);
ySpeed = std::clamp(ySpeed, -1.0, 1.0);
// Compensate for gyro angle.
auto input =
wpi::math::Translation2d{wpi::units::meter_t{xSpeed}, wpi::units::meter_t{ySpeed}}.RotateBy(
-gyroAngle);
auto input = wpi::math::Translation2d{
wpi::units::meter_t{xSpeed},
wpi::units::meter_t{
ySpeed}}.RotateBy(-gyroAngle);
double wheelSpeeds[4];
wheelSpeeds[kFrontLeft] = input.X().value() + input.Y().value() + zRotation;

View File

@@ -45,10 +45,10 @@ namespace {
template <typename Topic>
class MatchDataSenderEntry {
public:
MatchDataSenderEntry(const std::shared_ptr<wpi::nt::NetworkTable>& table,
std::string_view key,
typename Topic::ParamType initialVal,
wpi::util::json topicProperties = wpi::util::json::object())
MatchDataSenderEntry(
const std::shared_ptr<wpi::nt::NetworkTable>& table, std::string_view key,
typename Topic::ParamType initialVal,
wpi::util::json topicProperties = wpi::util::json::object())
: publisher{Topic{table->GetTopic(key)}.PublishEx(Topic::kTypeString,
topicProperties)},
prevVal{initialVal} {
@@ -80,13 +80,17 @@ struct MatchDataSender {
MatchDataSenderEntry<wpi::nt::StringTopic> gameSpecificMessage{
table, "GameSpecificMessage", ""};
MatchDataSenderEntry<wpi::nt::StringTopic> eventName{table, "EventName", ""};
MatchDataSenderEntry<wpi::nt::IntegerTopic> matchNumber{table, "MatchNumber", 0};
MatchDataSenderEntry<wpi::nt::IntegerTopic> replayNumber{table, "ReplayNumber", 0};
MatchDataSenderEntry<wpi::nt::IntegerTopic> matchNumber{table, "MatchNumber",
0};
MatchDataSenderEntry<wpi::nt::IntegerTopic> replayNumber{table,
"ReplayNumber", 0};
MatchDataSenderEntry<wpi::nt::IntegerTopic> matchType{table, "MatchType", 0};
MatchDataSenderEntry<wpi::nt::BooleanTopic> alliance{table, "IsRedAlliance", true};
MatchDataSenderEntry<wpi::nt::IntegerTopic> station{table, "StationNumber", 1};
MatchDataSenderEntry<wpi::nt::IntegerTopic> controlWord{table, "FMSControlData",
0};
MatchDataSenderEntry<wpi::nt::BooleanTopic> alliance{table, "IsRedAlliance",
true};
MatchDataSenderEntry<wpi::nt::IntegerTopic> station{table, "StationNumber",
1};
MatchDataSenderEntry<wpi::nt::IntegerTopic> controlWord{table,
"FMSControlData", 0};
};
class JoystickLogSender {
@@ -206,7 +210,8 @@ bool DriverStation::GetStickButton(int stick, int button) {
return false;
}
if (button < 0 || button >= 64) {
WPILIB_ReportError(warn::BadJoystickIndex, "button {} out of range", button);
WPILIB_ReportError(warn::BadJoystickIndex, "button {} out of range",
button);
return false;
}
@@ -234,7 +239,8 @@ std::optional<bool> DriverStation::GetStickButtonIfAvailable(int stick,
return false;
}
if (button < 0 || button >= 64) {
WPILIB_ReportError(warn::BadJoystickIndex, "button {} out of range", button);
WPILIB_ReportError(warn::BadJoystickIndex, "button {} out of range",
button);
return false;
}
@@ -256,7 +262,8 @@ bool DriverStation::GetStickButtonPressed(int stick, int button) {
return false;
}
if (button < 0 || button >= 64) {
WPILIB_ReportError(warn::BadJoystickIndex, "button {} out of range", button);
WPILIB_ReportError(warn::BadJoystickIndex, "button {} out of range",
button);
return false;
}
@@ -289,7 +296,8 @@ bool DriverStation::GetStickButtonReleased(int stick, int button) {
return false;
}
if (button < 0 || button >= 64) {
WPILIB_ReportError(warn::BadJoystickIndex, "button {} out of range", button);
WPILIB_ReportError(warn::BadJoystickIndex, "button {} out of range",
button);
return false;
}

View File

@@ -15,7 +15,8 @@ using namespace wpi;
GenericHID::GenericHID(int port) {
if (port < 0 || port >= DriverStation::kJoystickPorts) {
throw WPILIB_MakeError(warn::BadJoystickIndex, "port {} out of range", port);
throw WPILIB_MakeError(warn::BadJoystickIndex, "port {} out of range",
port);
}
m_port = port;
}

View File

@@ -25,7 +25,7 @@ EventLoop::EventLoop() {}
void EventLoop::Bind(wpi::util::unique_function<void()> action) {
if (m_running) {
throw WPILIB_MakeError(err::Error,
"Cannot bind EventLoop while it is running");
"Cannot bind EventLoop while it is running");
}
m_bindings.emplace_back(std::move(action));
}
@@ -40,7 +40,7 @@ void EventLoop::Poll() {
void EventLoop::Clear() {
if (m_running) {
throw WPILIB_MakeError(err::Error,
"Cannot clear EventLoop while it is running");
"Cannot clear EventLoop while it is running");
}
m_bindings.clear();
}

View File

@@ -15,9 +15,9 @@ ADXL345_I2C::ADXL345_I2C(I2C::Port port, Range range, int deviceAddress)
: m_i2c(port, deviceAddress),
m_simDevice("Accel:ADXL345_I2C", port, deviceAddress) {
if (m_simDevice) {
m_simRange = m_simDevice.CreateEnumDouble("range", wpi::hal::SimDevice::kOutput,
{"2G", "4G", "8G", "16G"},
{2.0, 4.0, 8.0, 16.0}, 0);
m_simRange = m_simDevice.CreateEnumDouble(
"range", wpi::hal::SimDevice::kOutput, {"2G", "4G", "8G", "16G"},
{2.0, 4.0, 8.0, 16.0}, 0);
m_simX = m_simDevice.CreateDouble("x", wpi::hal::SimDevice::kInput, 0.0);
m_simY = m_simDevice.CreateDouble("y", wpi::hal::SimDevice::kInput, 0.0);
m_simZ = m_simDevice.CreateDouble("z", wpi::hal::SimDevice::kInput, 0.0);

View File

@@ -55,5 +55,5 @@ void AnalogAccelerometer::InitAccelerometer() {
HAL_ReportUsage("IO", m_analogInput->GetChannel(), "Accelerometer");
wpi::util::SendableRegistry::Add(this, "Accelerometer",
m_analogInput->GetChannel());
m_analogInput->GetChannel());
}

View File

@@ -23,7 +23,7 @@ CAN::CAN(int busId, int deviceId, int deviceManufacturer, int deviceType) {
busId, static_cast<HAL_CANManufacturer>(deviceManufacturer), deviceId,
static_cast<HAL_CANDeviceType>(deviceType), &status);
WPILIB_CheckErrorStatus(status, "device id {} mfg {} type {}", deviceId,
deviceManufacturer, deviceType);
deviceManufacturer, deviceType);
HAL_ReportUsage(
fmt::format("CAN[{}][{}][{}]", deviceType, deviceManufacturer, deviceId),

View File

@@ -25,10 +25,11 @@ SerialPort::SerialPort(int baudRate, Port port, int dataBits,
HAL_SetSerialDataBits(m_portHandle, dataBits, &status);
WPILIB_CheckErrorStatus(status, "SetSerialDataBits {}", dataBits);
HAL_SetSerialParity(m_portHandle, parity, &status);
WPILIB_CheckErrorStatus(status, "SetSerialParity {}", static_cast<int>(parity));
WPILIB_CheckErrorStatus(status, "SetSerialParity {}",
static_cast<int>(parity));
HAL_SetSerialStopBits(m_portHandle, stopBits, &status);
WPILIB_CheckErrorStatus(status, "SetSerialStopBits {}",
static_cast<int>(stopBits));
static_cast<int>(stopBits));
// Set the default timeout to 5 seconds.
SetTimeout(5_s);
@@ -55,10 +56,11 @@ SerialPort::SerialPort(int baudRate, std::string_view portName, Port port,
HAL_SetSerialDataBits(m_portHandle, dataBits, &status);
WPILIB_CheckErrorStatus(status, "SetSerialDataBits {}", dataBits);
HAL_SetSerialParity(m_portHandle, parity, &status);
WPILIB_CheckErrorStatus(status, "SetSerialParity {}", static_cast<int>(parity));
WPILIB_CheckErrorStatus(status, "SetSerialParity {}",
static_cast<int>(parity));
HAL_SetSerialStopBits(m_portHandle, stopBits, &status);
WPILIB_CheckErrorStatus(status, "SetSerialStopBits {}",
static_cast<int>(stopBits));
static_cast<int>(stopBits));
// Set the default timeout to 5 seconds.
SetTimeout(5_s);
@@ -75,7 +77,7 @@ void SerialPort::SetFlowControl(SerialPort::FlowControl flowControl) {
int32_t status = 0;
HAL_SetSerialFlowControl(m_portHandle, flowControl, &status);
WPILIB_CheckErrorStatus(status, "SetFlowControl {}",
static_cast<int>(flowControl));
static_cast<int>(flowControl));
}
void SerialPort::EnableTermination(char terminator) {
@@ -137,7 +139,8 @@ void SerialPort::SetWriteBufferSize(int size) {
void SerialPort::SetWriteBufferMode(SerialPort::WriteBufferMode mode) {
int32_t status = 0;
HAL_SetSerialWriteMode(m_portHandle, mode, &status);
WPILIB_CheckErrorStatus(status, "SetWriteBufferMode {}", static_cast<int>(mode));
WPILIB_CheckErrorStatus(status, "SetWriteBufferMode {}",
static_cast<int>(mode));
}
void SerialPort::Flush() {

View File

@@ -82,7 +82,7 @@ void PWM::SetOutputPeriod(OutputPeriod mult) {
break;
default:
throw WPILIB_MakeError(err::InvalidParameter, "OutputPeriod value {}",
static_cast<int>(mult));
static_cast<int>(mult));
}
WPILIB_CheckErrorStatus(status, "Channel {}", m_channel);
@@ -101,5 +101,7 @@ void PWM::InitSendable(wpi::util::SendableBuilder& builder) {
builder.SetActuator(true);
builder.AddDoubleProperty(
"Value", [=, this] { return GetPulseTime().value(); },
[=, this](double value) { SetPulseTime(wpi::units::millisecond_t{value}); });
[=, this](double value) {
SetPulseTime(wpi::units::millisecond_t{value});
});
}

View File

@@ -55,7 +55,7 @@ LEDPattern LEDPattern::Reversed() {
LEDPattern LEDPattern::OffsetBy(int offset) {
return MapIndex([offset](size_t bufLen, size_t i) {
return wpi::math::FloorMod(static_cast<int>(i) + offset,
static_cast<int>(bufLen));
static_cast<int>(bufLen));
});
}
@@ -74,7 +74,7 @@ LEDPattern LEDPattern::ScrollAtRelativeSpeed(wpi::units::hertz_t velocity) {
int offset = static_cast<int>(std::floor(t * bufLen));
return wpi::math::FloorMod(static_cast<int>(i) + offset,
static_cast<int>(bufLen));
static_cast<int>(bufLen));
});
}
@@ -95,11 +95,12 @@ LEDPattern LEDPattern::ScrollAtAbsoluteSpeed(
auto offset = static_cast<int64_t>(now) / microsPerLed;
return wpi::math::FloorMod(static_cast<int>(i) + offset,
static_cast<int>(bufLen));
static_cast<int>(bufLen));
});
}
LEDPattern LEDPattern::Blink(wpi::units::second_t onTime, wpi::units::second_t offTime) {
LEDPattern LEDPattern::Blink(wpi::units::second_t onTime,
wpi::units::second_t offTime) {
auto totalMicros = wpi::units::microsecond_t{onTime + offTime}.to<uint64_t>();
auto onMicros = wpi::units::microsecond_t{onTime}.to<uint64_t>();

View File

@@ -158,18 +158,20 @@ void MotorSafety::Check() {
}
if (stopTime < Timer::GetFPGATimestamp()) {
WPILIB_ReportError(err::Timeout,
"{}... Output not updated often enough. See "
"https://docs.wpilib.org/motorsafety for more information.",
GetDescription());
WPILIB_ReportError(
err::Timeout,
"{}... Output not updated often enough. See "
"https://docs.wpilib.org/motorsafety for more information.",
GetDescription());
try {
StopMotor();
} catch (wpi::RuntimeError& e) {
e.Report();
} catch (std::exception& e) {
WPILIB_ReportError(err::Error, "{} StopMotor threw unexpected exception: {}",
GetDescription(), e.what());
WPILIB_ReportError(err::Error,
"{} StopMotor threw unexpected exception: {}",
GetDescription(), e.what());
}
}
}

View File

@@ -63,13 +63,15 @@ void Compressor::EnableDigital() {
m_module->EnableCompressorDigital();
}
void Compressor::EnableAnalog(wpi::units::pounds_per_square_inch_t minPressure,
wpi::units::pounds_per_square_inch_t maxPressure) {
void Compressor::EnableAnalog(
wpi::units::pounds_per_square_inch_t minPressure,
wpi::units::pounds_per_square_inch_t maxPressure) {
m_module->EnableCompressorAnalog(minPressure, maxPressure);
}
void Compressor::EnableHybrid(wpi::units::pounds_per_square_inch_t minPressure,
wpi::units::pounds_per_square_inch_t maxPressure) {
void Compressor::EnableHybrid(
wpi::units::pounds_per_square_inch_t minPressure,
wpi::units::pounds_per_square_inch_t maxPressure) {
m_module->EnableCompressorHybrid(minPressure, maxPressure);
}

View File

@@ -23,11 +23,11 @@ DoubleSolenoid::DoubleSolenoid(int busId, int module,
m_reverseChannel{reverseChannel} {
if (!m_module->CheckSolenoidChannel(m_forwardChannel)) {
throw WPILIB_MakeError(err::ChannelIndexOutOfRange, "Channel {}",
m_forwardChannel);
m_forwardChannel);
}
if (!m_module->CheckSolenoidChannel(m_reverseChannel)) {
throw WPILIB_MakeError(err::ChannelIndexOutOfRange, "Channel {}",
m_reverseChannel);
m_reverseChannel);
}
m_forwardMask = 1 << forwardChannel;
@@ -37,14 +37,15 @@ DoubleSolenoid::DoubleSolenoid(int busId, int module,
int allocMask = m_module->CheckAndReserveSolenoids(m_mask);
if (allocMask != 0) {
if (allocMask == m_mask) {
throw WPILIB_MakeError(err::ResourceAlreadyAllocated, "Channels {} and {}",
m_forwardChannel, m_reverseChannel);
throw WPILIB_MakeError(err::ResourceAlreadyAllocated,
"Channels {} and {}", m_forwardChannel,
m_reverseChannel);
} else if (allocMask == m_forwardMask) {
throw WPILIB_MakeError(err::ResourceAlreadyAllocated, "Channel {}",
m_forwardChannel);
m_forwardChannel);
} else {
throw WPILIB_MakeError(err::ResourceAlreadyAllocated, "Channel {}",
m_reverseChannel);
m_reverseChannel);
}
}
@@ -52,8 +53,8 @@ DoubleSolenoid::DoubleSolenoid(int busId, int module,
fmt::format("Solenoid[{},{}]", m_forwardChannel, m_reverseChannel),
"DoubleSolenoid");
wpi::util::SendableRegistry::Add(this, "DoubleSolenoid",
m_module->GetModuleNumber(), m_forwardChannel);
wpi::util::SendableRegistry::Add(
this, "DoubleSolenoid", m_module->GetModuleNumber(), m_forwardChannel);
}
DoubleSolenoid::DoubleSolenoid(int busId, PneumaticsModuleType moduleType,

View File

@@ -26,21 +26,22 @@
using namespace wpi;
/** Converts volts to PSI per the REV Analog Pressure Sensor datasheet. */
wpi::units::pounds_per_square_inch_t VoltsToPSI(wpi::units::volt_t sensorVoltage,
wpi::units::volt_t supplyVoltage) {
wpi::units::pounds_per_square_inch_t VoltsToPSI(
wpi::units::volt_t sensorVoltage, wpi::units::volt_t supplyVoltage) {
return wpi::units::pounds_per_square_inch_t{
250 * (sensorVoltage.value() / supplyVoltage.value()) - 25};
}
/** Converts PSI to volts per the REV Analog Pressure Sensor datasheet. */
wpi::units::volt_t PSIToVolts(wpi::units::pounds_per_square_inch_t pressure,
wpi::units::volt_t supplyVoltage) {
wpi::units::volt_t supplyVoltage) {
return wpi::units::volt_t{supplyVoltage.value() *
(0.004 * pressure.value() + 0.1)};
(0.004 * pressure.value() + 0.1)};
}
wpi::util::mutex PneumaticHub::m_handleLock;
std::unique_ptr<wpi::util::DenseMap<int, std::weak_ptr<PneumaticHub::DataStore>>[]>
std::unique_ptr<
wpi::util::DenseMap<int, std::weak_ptr<PneumaticHub::DataStore>>[]>
PneumaticHub::m_handleMaps = nullptr;
// Always called under lock, so we can avoid the double lock from the magic
@@ -49,10 +50,11 @@ std::weak_ptr<PneumaticHub::DataStore>& PneumaticHub::GetDataStore(int busId,
int module) {
int32_t numBuses = HAL_GetNumCanBuses();
WPILIB_AssertMessage(busId >= 0 && busId < numBuses,
"Bus {} out of range. Must be [0-{}).", busId, numBuses);
"Bus {} out of range. Must be [0-{}).", busId, numBuses);
if (!m_handleMaps) {
m_handleMaps = std::make_unique<
wpi::util::DenseMap<int, std::weak_ptr<PneumaticHub::DataStore>>[]>(numBuses);
wpi::util::DenseMap<int, std::weak_ptr<PneumaticHub::DataStore>>[]>(
numBuses);
}
return m_handleMaps[busId][module];
}
@@ -138,17 +140,17 @@ void PneumaticHub::EnableCompressorAnalog(
wpi::units::pounds_per_square_inch_t maxPressure) {
if (minPressure >= maxPressure) {
throw WPILIB_MakeError(err::InvalidParameter,
"maxPressure must be greater than minPressure");
"maxPressure must be greater than minPressure");
}
if (minPressure < 0_psi || minPressure > 120_psi) {
throw WPILIB_MakeError(err::ParameterOutOfRange,
"minPressure must be between 0 and 120 PSI, got {}",
minPressure);
"minPressure must be between 0 and 120 PSI, got {}",
minPressure);
}
if (maxPressure < 0_psi || maxPressure > 120_psi) {
throw WPILIB_MakeError(err::ParameterOutOfRange,
"maxPressure must be between 0 and 120 PSI, got {}",
maxPressure);
"maxPressure must be between 0 and 120 PSI, got {}",
maxPressure);
}
// Send the voltage as it would be if the 5V rail was at exactly 5V.
@@ -168,17 +170,17 @@ void PneumaticHub::EnableCompressorHybrid(
wpi::units::pounds_per_square_inch_t maxPressure) {
if (minPressure >= maxPressure) {
throw WPILIB_MakeError(err::InvalidParameter,
"maxPressure must be greater than minPressure");
"maxPressure must be greater than minPressure");
}
if (minPressure < 0_psi || minPressure > 120_psi) {
throw WPILIB_MakeError(err::ParameterOutOfRange,
"minPressure must be between 0 and 120 PSI, got {}",
minPressure);
"minPressure must be between 0 and 120 PSI, got {}",
minPressure);
}
if (maxPressure < 0_psi || maxPressure > 120_psi) {
throw WPILIB_MakeError(err::ParameterOutOfRange,
"maxPressure must be between 0 and 120 PSI, got {}",
maxPressure);
"maxPressure must be between 0 and 120 PSI, got {}",
maxPressure);
}
// Send the voltage as it would be if the 5V rail was at exactly 5V.
@@ -245,7 +247,8 @@ void PneumaticHub::FireOneShot(int index) {
WPILIB_ReportError(status, "Module {}", m_module);
}
void PneumaticHub::SetOneShotDuration(int index, wpi::units::second_t duration) {
void PneumaticHub::SetOneShotDuration(int index,
wpi::units::second_t duration) {
m_dataStore->m_oneShotDurMs[index] = duration;
}
@@ -360,7 +363,7 @@ bool PneumaticHub::Faults::GetChannelFault(int channel) const {
return Channel15Fault != 0;
default:
throw WPILIB_MakeError(err::ChannelIndexOutOfRange,
"Pneumatics fault channel out of bounds!");
"Pneumatics fault channel out of bounds!");
}
}
@@ -405,13 +408,15 @@ wpi::units::volt_t PneumaticHub::GetAnalogVoltage(int channel) const {
return wpi::units::volt_t{voltage};
}
wpi::units::pounds_per_square_inch_t PneumaticHub::GetPressure(int channel) const {
wpi::units::pounds_per_square_inch_t PneumaticHub::GetPressure(
int channel) const {
int32_t status = 0;
auto sensorVoltage = HAL_GetREVPHAnalogVoltage(m_handle, channel, &status);
WPILIB_ReportError(status, "Module {}", m_module);
auto supplyVoltage = HAL_GetREVPH5VVoltage(m_handle, &status);
WPILIB_ReportError(status, "Module {}", m_module);
return VoltsToPSI(wpi::units::volt_t{sensorVoltage}, wpi::units::volt_t{supplyVoltage});
return VoltsToPSI(wpi::units::volt_t{sensorVoltage},
wpi::units::volt_t{supplyVoltage});
}
Solenoid PneumaticHub::MakeSolenoid(int channel) {

View File

@@ -35,7 +35,7 @@ std::shared_ptr<PneumaticsBase> PneumaticsBase::GetForType(
return PneumaticHub::GetForModule(busId, module);
}
throw WPILIB_MakeError(err::InvalidParameter, "{}",
static_cast<int>(moduleType));
static_cast<int>(moduleType));
}
int PneumaticsBase::GetDefaultForType(PneumaticsModuleType moduleType) {
@@ -45,5 +45,5 @@ int PneumaticsBase::GetDefaultForType(PneumaticsModuleType moduleType) {
return SensorUtil::GetDefaultREVPHModule();
}
throw WPILIB_MakeError(err::InvalidParameter, "{}",
static_cast<int>(moduleType));
static_cast<int>(moduleType));
}

View File

@@ -23,8 +23,8 @@
using namespace wpi;
wpi::util::mutex PneumaticsControlModule::m_handleLock;
std::unique_ptr<
wpi::util::DenseMap<int, std::weak_ptr<PneumaticsControlModule::DataStore>>[]>
std::unique_ptr<wpi::util::DenseMap<
int, std::weak_ptr<PneumaticsControlModule::DataStore>>[]>
PneumaticsControlModule::m_handleMaps = nullptr;
// Always called under lock, so we can avoid the double lock from the magic
@@ -33,7 +33,7 @@ std::weak_ptr<PneumaticsControlModule::DataStore>&
PneumaticsControlModule::GetDataStore(int busId, int module) {
int32_t numBuses = HAL_GetNumCanBuses();
WPILIB_AssertMessage(busId >= 0 && busId < numBuses,
"Bus {} out of range. Must be [0-{}).", busId, numBuses);
"Bus {} out of range. Must be [0-{}).", busId, numBuses);
if (!m_handleMaps) {
m_handleMaps = std::make_unique<wpi::util::DenseMap<
int, std::weak_ptr<PneumaticsControlModule::DataStore>>[]>(numBuses);
@@ -234,8 +234,8 @@ void PneumaticsControlModule::FireOneShot(int index) {
WPILIB_ReportError(status, "Module {}", m_module);
}
void PneumaticsControlModule::SetOneShotDuration(int index,
wpi::units::second_t duration) {
void PneumaticsControlModule::SetOneShotDuration(
int index, wpi::units::second_t duration) {
int32_t status = 0;
wpi::units::millisecond_t millis = duration;
HAL_SetCTREPCMOneShotDuration(m_handle, index, millis.to<int32_t>(), &status);
@@ -275,7 +275,8 @@ void PneumaticsControlModule::UnreserveCompressor() {
m_dataStore->m_compressorReserved = false;
}
wpi::units::volt_t PneumaticsControlModule::GetAnalogVoltage(int channel) const {
wpi::units::volt_t PneumaticsControlModule::GetAnalogVoltage(
int channel) const {
return 0_V;
}

View File

@@ -19,17 +19,19 @@ Solenoid::Solenoid(int busId, int module, PneumaticsModuleType moduleType,
: m_module{PneumaticsBase::GetForType(busId, module, moduleType)},
m_channel{channel} {
if (!m_module->CheckSolenoidChannel(m_channel)) {
throw WPILIB_MakeError(err::ChannelIndexOutOfRange, "Channel {}", m_channel);
throw WPILIB_MakeError(err::ChannelIndexOutOfRange, "Channel {}",
m_channel);
}
m_mask = 1 << channel;
if (m_module->CheckAndReserveSolenoids(m_mask) != 0) {
throw WPILIB_MakeError(err::ResourceAlreadyAllocated, "Channel {}", m_channel);
throw WPILIB_MakeError(err::ResourceAlreadyAllocated, "Channel {}",
m_channel);
}
m_module->ReportUsage(fmt::format("Solenoid[{}]", m_channel), "Solenoid");
wpi::util::SendableRegistry::Add(this, "Solenoid", m_module->GetModuleNumber(),
m_channel);
wpi::util::SendableRegistry::Add(this, "Solenoid",
m_module->GetModuleNumber(), m_channel);
}
Solenoid::Solenoid(int busId, PneumaticsModuleType moduleType, int channel)

View File

@@ -246,7 +246,7 @@ bool PowerDistribution::Faults::GetBreakerFault(int channel) const {
return Channel23BreakerFault != 0;
default:
throw WPILIB_MakeError(err::ChannelIndexOutOfRange,
"Power distribution fault channel out of bounds!");
"Power distribution fault channel out of bounds!");
}
}
@@ -302,7 +302,7 @@ bool PowerDistribution::StickyFaults::GetBreakerFault(int channel) const {
return Channel23BreakerFault != 0;
default:
throw WPILIB_MakeError(err::ChannelIndexOutOfRange,
"Power distribution fault channel out of bounds!");
"Power distribution fault channel out of bounds!");
}
}

View File

@@ -58,7 +58,8 @@ AnalogEncoder::AnalogEncoder(std::shared_ptr<AnalogInput> analogInput,
}
void AnalogEncoder::Init(double fullRange, double expectedZero) {
m_simDevice = wpi::hal::SimDevice{"AnalogEncoder", m_analogInput->GetChannel()};
m_simDevice =
wpi::hal::SimDevice{"AnalogEncoder", m_analogInput->GetChannel()};
if (m_simDevice) {
m_simPosition = m_simDevice.CreateDouble("Position", false, 0.0);
@@ -70,7 +71,7 @@ void AnalogEncoder::Init(double fullRange, double expectedZero) {
HAL_ReportUsage("IO", m_analogInput->GetChannel(), "AnalogEncoder");
wpi::util::SendableRegistry::Add(this, "Analog Encoder",
m_analogInput->GetChannel());
m_analogInput->GetChannel());
}
double AnalogEncoder::Get() const {

View File

@@ -23,9 +23,9 @@ AnalogPotentiometer::AnalogPotentiometer(int channel, double fullRange,
AnalogPotentiometer::AnalogPotentiometer(AnalogInput* input, double fullRange,
double offset)
: AnalogPotentiometer(
std::shared_ptr<AnalogInput>(input, wpi::util::NullDeleter<AnalogInput>()),
fullRange, offset) {}
: AnalogPotentiometer(std::shared_ptr<AnalogInput>(
input, wpi::util::NullDeleter<AnalogInput>()),
fullRange, offset) {}
AnalogPotentiometer::AnalogPotentiometer(std::shared_ptr<AnalogInput> input,
double fullRange, double offset)
@@ -33,7 +33,7 @@ AnalogPotentiometer::AnalogPotentiometer(std::shared_ptr<AnalogInput> input,
m_fullRange(fullRange),
m_offset(offset) {
wpi::util::SendableRegistry::Add(this, "AnalogPotentiometer",
m_analog_input->GetChannel());
m_analog_input->GetChannel());
}
double AnalogPotentiometer::Get() const {

View File

@@ -61,19 +61,19 @@ DutyCycleEncoder::DutyCycleEncoder(std::shared_ptr<DutyCycle> dutyCycle,
void DutyCycleEncoder::Init(double fullRange, double expectedZero) {
m_simDevice = wpi::hal::SimDevice{"DutyCycle:DutyCycleEncoder",
m_dutyCycle->GetSourceChannel()};
m_dutyCycle->GetSourceChannel()};
if (m_simDevice) {
m_simPosition = m_simDevice.CreateDouble("Position", false, 0.0);
m_simIsConnected =
m_simDevice.CreateBoolean("Connected", wpi::hal::SimDevice::kInput, true);
m_simIsConnected = m_simDevice.CreateBoolean(
"Connected", wpi::hal::SimDevice::kInput, true);
}
m_fullRange = fullRange;
m_expectedZero = expectedZero;
wpi::util::SendableRegistry::Add(this, "DutyCycle Encoder",
m_dutyCycle->GetSourceChannel());
m_dutyCycle->GetSourceChannel());
}
double DutyCycleEncoder::Get() const {

View File

@@ -193,7 +193,8 @@ void IterativeRobotBase::LoopFunc() {
}
void IterativeRobotBase::PrintLoopOverrunMessage() {
WPILIB_ReportError(err::Error, "Loop time of {:.6f}s overrun", m_period.value());
WPILIB_ReportError(err::Error, "Loop time of {:.6f}s overrun",
m_period.value());
}
void IterativeRobotBase::PrintWatchdogEpochs() {

View File

@@ -75,7 +75,8 @@ void TimedRobot::EndCompetition() {
HAL_StopNotifier(m_notifier, &status);
}
TimedRobot::TimedRobot(wpi::units::second_t period) : IterativeRobotBase(period) {
TimedRobot::TimedRobot(wpi::units::second_t period)
: IterativeRobotBase(period) {
m_startTime = std::chrono::microseconds{RobotController::GetFPGATime()};
AddPeriodic([=, this] { LoopFunc(); }, period);
@@ -87,7 +88,8 @@ TimedRobot::TimedRobot(wpi::units::second_t period) : IterativeRobotBase(period)
HAL_ReportUsage("Framework", "TimedRobot");
}
TimedRobot::TimedRobot(wpi::units::hertz_t frequency) : TimedRobot{1 / frequency} {}
TimedRobot::TimedRobot(wpi::units::hertz_t frequency)
: TimedRobot{1 / frequency} {}
TimedRobot::~TimedRobot() {
if (m_notifier != HAL_kInvalidHandle) {
@@ -102,7 +104,8 @@ uint64_t TimedRobot::GetLoopStartTime() {
}
void TimedRobot::AddPeriodic(std::function<void()> callback,
wpi::units::second_t period, wpi::units::second_t offset) {
wpi::units::second_t period,
wpi::units::second_t offset) {
m_callbacks.emplace(
callback, m_startTime,
std::chrono::microseconds{static_cast<int64_t>(period.value() * 1e6)},

View File

@@ -17,9 +17,9 @@ void TimesliceRobot::Schedule(std::function<void()> func,
wpi::units::second_t allocation) {
if (m_nextOffset + allocation > m_controllerPeriod) {
throw WPILIB_MakeError(err::Error,
"Function scheduled at offset {} with allocation {} "
"exceeded controller period of {}\n",
m_nextOffset, allocation, m_controllerPeriod);
"Function scheduled at offset {} with allocation {} "
"exceeded controller period of {}\n",
m_nextOffset, allocation, m_controllerPeriod);
}
AddPeriodic(func, m_controllerPeriod, m_nextOffset);

View File

@@ -58,13 +58,15 @@ wpi::units::radians_per_second_t DCMotorSim::GetAngularVelocity() const {
return wpi::units::radians_per_second_t{GetOutput(1)};
}
wpi::units::radians_per_second_squared_t DCMotorSim::GetAngularAcceleration() const {
wpi::units::radians_per_second_squared_t DCMotorSim::GetAngularAcceleration()
const {
return wpi::units::radians_per_second_squared_t{
(m_plant.A() * m_x + m_plant.B() * m_u)(1, 0)};
}
wpi::units::newton_meter_t DCMotorSim::GetTorque() const {
return wpi::units::newton_meter_t{GetAngularAcceleration().value() * m_j.value()};
return wpi::units::newton_meter_t{GetAngularAcceleration().value() *
m_j.value()};
}
wpi::units::ampere_t DCMotorSim::GetCurrentDraw() const {

View File

@@ -16,8 +16,9 @@ using namespace wpi;
using namespace wpi::sim;
DifferentialDrivetrainSim::DifferentialDrivetrainSim(
wpi::math::LinearSystem<2, 2, 2> plant, wpi::units::meter_t trackwidth, wpi::math::DCMotor driveMotor,
double gearRatio, wpi::units::meter_t wheelRadius,
wpi::math::LinearSystem<2, 2, 2> plant, wpi::units::meter_t trackwidth,
wpi::math::DCMotor driveMotor, double gearRatio,
wpi::units::meter_t wheelRadius,
const std::array<double, 7>& measurementStdDevs)
: m_plant(std::move(plant)),
m_rb(trackwidth / 2.0),
@@ -32,9 +33,10 @@ DifferentialDrivetrainSim::DifferentialDrivetrainSim(
}
DifferentialDrivetrainSim::DifferentialDrivetrainSim(
wpi::math::DCMotor driveMotor, double gearing, wpi::units::kilogram_square_meter_t J,
wpi::units::kilogram_t mass, wpi::units::meter_t wheelRadius,
wpi::units::meter_t trackwidth, const std::array<double, 7>& measurementStdDevs)
wpi::math::DCMotor driveMotor, double gearing,
wpi::units::kilogram_square_meter_t J, wpi::units::kilogram_t mass,
wpi::units::meter_t wheelRadius, wpi::units::meter_t trackwidth,
const std::array<double, 7>& measurementStdDevs)
: DifferentialDrivetrainSim(
wpi::math::LinearSystemId::DrivetrainVelocitySystem(
driveMotor, mass, wheelRadius, trackwidth / 2.0, J, gearing),
@@ -42,8 +44,8 @@ DifferentialDrivetrainSim::DifferentialDrivetrainSim(
Eigen::Vector2d DifferentialDrivetrainSim::ClampInput(
const Eigen::Vector2d& u) {
return wpi::math::DesaturateInputVector<2>(u,
wpi::RobotController::GetInputVoltage());
return wpi::math::DesaturateInputVector<2>(
u, wpi::RobotController::GetInputVoltage());
}
void DifferentialDrivetrainSim::SetInputs(wpi::units::volt_t leftVoltage,
@@ -57,7 +59,8 @@ void DifferentialDrivetrainSim::SetGearing(double newGearing) {
}
void DifferentialDrivetrainSim::Update(wpi::units::second_t dt) {
m_x = wpi::math::RKDP([this](auto& x, auto& u) { return Dynamics(x, u); }, m_x, m_u, dt);
m_x = wpi::math::RKDP([this](auto& x, auto& u) { return Dynamics(x, u); },
m_x, m_u, dt);
m_y = m_x + wpi::math::MakeWhiteNoiseVector<7>(m_measurementStdDevs);
}
@@ -87,22 +90,24 @@ wpi::math::Rotation2d DifferentialDrivetrainSim::GetHeading() const {
wpi::math::Pose2d DifferentialDrivetrainSim::GetPose() const {
return wpi::math::Pose2d{wpi::units::meter_t{GetOutput(State::kX)},
wpi::units::meter_t{GetOutput(State::kY)}, GetHeading()};
wpi::units::meter_t{GetOutput(State::kY)},
GetHeading()};
}
wpi::units::ampere_t DifferentialDrivetrainSim::GetLeftCurrentDraw() const {
return m_motor.Current(wpi::units::radians_per_second_t{m_x(State::kLeftVelocity) *
m_currentGearing /
m_wheelRadius.value()},
wpi::units::volt_t{m_u(0)}) *
return m_motor.Current(
wpi::units::radians_per_second_t{m_x(State::kLeftVelocity) *
m_currentGearing /
m_wheelRadius.value()},
wpi::units::volt_t{m_u(0)}) *
wpi::util::sgn(m_u(0));
}
wpi::units::ampere_t DifferentialDrivetrainSim::GetRightCurrentDraw() const {
return m_motor.Current(
wpi::units::radians_per_second_t{m_x(State::kRightVelocity) *
m_currentGearing /
m_wheelRadius.value()},
m_currentGearing /
m_wheelRadius.value()},
wpi::units::volt_t{m_u(1)}) *
wpi::util::sgn(m_u(1));
}
@@ -123,8 +128,8 @@ void DifferentialDrivetrainSim::SetPose(const wpi::math::Pose2d& pose) {
m_x(State::kRightPosition) = 0;
}
wpi::math::Vectord<7> DifferentialDrivetrainSim::Dynamics(const wpi::math::Vectord<7>& x,
const Eigen::Vector2d& u) {
wpi::math::Vectord<7> DifferentialDrivetrainSim::Dynamics(
const wpi::math::Vectord<7>& x, const Eigen::Vector2d& u) {
// Because G² can be factored out of A, we can divide by the old ratio
// squared and multiply by the new ratio squared to get a new drivetrain
// model.

View File

@@ -13,7 +13,8 @@ using namespace wpi;
using namespace wpi::sim;
ElevatorSim::ElevatorSim(const wpi::math::LinearSystem<2, 1, 2>& plant,
const wpi::math::DCMotor& gearbox, wpi::units::meter_t minHeight,
const wpi::math::DCMotor& gearbox,
wpi::units::meter_t minHeight,
wpi::units::meter_t maxHeight, bool simulateGravity,
wpi::units::meter_t startingHeight,
const std::array<double, 2>& measurementStdDevs)
@@ -27,12 +28,13 @@ ElevatorSim::ElevatorSim(const wpi::math::LinearSystem<2, 1, 2>& plant,
ElevatorSim::ElevatorSim(const wpi::math::DCMotor& gearbox, double gearing,
wpi::units::kilogram_t carriageMass,
wpi::units::meter_t drumRadius, wpi::units::meter_t minHeight,
wpi::units::meter_t drumRadius,
wpi::units::meter_t minHeight,
wpi::units::meter_t maxHeight, bool simulateGravity,
wpi::units::meter_t startingHeight,
const std::array<double, 2>& measurementStdDevs)
: ElevatorSim(wpi::math::LinearSystemId::ElevatorSystem(gearbox, carriageMass,
drumRadius, gearing),
: ElevatorSim(wpi::math::LinearSystemId::ElevatorSystem(
gearbox, carriageMass, drumRadius, gearing),
gearbox, minHeight, maxHeight, simulateGravity,
startingHeight, measurementStdDevs) {}
@@ -41,18 +43,19 @@ template <typename Distance>
std::same_as<wpi::units::radian, Distance>
ElevatorSim::ElevatorSim(decltype(1_V / Velocity_t<Distance>(1)) kV,
decltype(1_V / Acceleration_t<Distance>(1)) kA,
const wpi::math::DCMotor& gearbox, wpi::units::meter_t minHeight,
const wpi::math::DCMotor& gearbox,
wpi::units::meter_t minHeight,
wpi::units::meter_t maxHeight, bool simulateGravity,
wpi::units::meter_t startingHeight,
const std::array<double, 2>& measurementStdDevs)
: ElevatorSim(wpi::math::LinearSystemId::IdentifyPositionSystem(kV, kA), gearbox,
minHeight, maxHeight, simulateGravity, startingHeight,
measurementStdDevs) {}
: ElevatorSim(wpi::math::LinearSystemId::IdentifyPositionSystem(kV, kA),
gearbox, minHeight, maxHeight, simulateGravity,
startingHeight, measurementStdDevs) {}
void ElevatorSim::SetState(wpi::units::meter_t position,
wpi::units::meters_per_second_t velocity) {
SetState(
wpi::math::Vectord<2>{std::clamp(position, m_minHeight, m_maxHeight), velocity});
SetState(wpi::math::Vectord<2>{std::clamp(position, m_minHeight, m_maxHeight),
velocity});
}
bool ElevatorSim::WouldHitLowerLimit(wpi::units::meter_t elevatorHeight) const {
@@ -101,10 +104,12 @@ void ElevatorSim::SetInputVoltage(wpi::units::volt_t voltage) {
ClampInput(wpi::RobotController::GetBatteryVoltage().value());
}
wpi::math::Vectord<2> ElevatorSim::UpdateX(const wpi::math::Vectord<2>& currentXhat,
const wpi::math::Vectord<1>& u, wpi::units::second_t dt) {
wpi::math::Vectord<2> ElevatorSim::UpdateX(
const wpi::math::Vectord<2>& currentXhat, const wpi::math::Vectord<1>& u,
wpi::units::second_t dt) {
auto updatedXhat = wpi::math::RKDP(
[&](const wpi::math::Vectord<2>& x, const wpi::math::Vectord<1>& u_) -> wpi::math::Vectord<2> {
[&](const wpi::math::Vectord<2>& x,
const wpi::math::Vectord<1>& u_) -> wpi::math::Vectord<2> {
wpi::math::Vectord<2> xdot = m_plant.A() * x + m_plant.B() * u;
if (m_simulateGravity) {

View File

@@ -51,7 +51,8 @@ wpi::units::radians_per_second_squared_t FlywheelSim::GetAngularAcceleration()
}
wpi::units::newton_meter_t FlywheelSim::GetTorque() const {
return wpi::units::newton_meter_t{GetAngularAcceleration().value() * m_j.value()};
return wpi::units::newton_meter_t{GetAngularAcceleration().value() *
m_j.value()};
}
wpi::units::ampere_t FlywheelSim::GetCurrentDraw() const {

View File

@@ -25,7 +25,7 @@ std::shared_ptr<PneumaticsBaseSim> PneumaticsBaseSim::GetForType(
default:
throw WPILIB_MakeError(err::InvalidParameter, "{}",
static_cast<int>(module));
static_cast<int>(module));
}
}

View File

@@ -16,7 +16,8 @@ using namespace wpi;
using namespace wpi::sim;
SingleJointedArmSim::SingleJointedArmSim(
const wpi::math::LinearSystem<2, 1, 2>& system, const wpi::math::DCMotor& gearbox, double gearing,
const wpi::math::LinearSystem<2, 1, 2>& system,
const wpi::math::DCMotor& gearbox, double gearing,
wpi::units::meter_t armLength, wpi::units::radian_t minAngle,
wpi::units::radian_t maxAngle, bool simulateGravity,
wpi::units::radian_t startingAngle,
@@ -32,26 +33,29 @@ SingleJointedArmSim::SingleJointedArmSim(
}
SingleJointedArmSim::SingleJointedArmSim(
const wpi::math::DCMotor& gearbox, double gearing, wpi::units::kilogram_square_meter_t moi,
wpi::units::meter_t armLength, wpi::units::radian_t minAngle,
wpi::units::radian_t maxAngle, bool simulateGravity,
wpi::units::radian_t startingAngle,
const wpi::math::DCMotor& gearbox, double gearing,
wpi::units::kilogram_square_meter_t moi, wpi::units::meter_t armLength,
wpi::units::radian_t minAngle, wpi::units::radian_t maxAngle,
bool simulateGravity, wpi::units::radian_t startingAngle,
const std::array<double, 2>& measurementStdDevs)
: SingleJointedArmSim(
wpi::math::LinearSystemId::SingleJointedArmSystem(gearbox, moi, gearing),
gearbox, gearing, armLength, minAngle, maxAngle, simulateGravity,
startingAngle, measurementStdDevs) {}
: SingleJointedArmSim(wpi::math::LinearSystemId::SingleJointedArmSystem(
gearbox, moi, gearing),
gearbox, gearing, armLength, minAngle, maxAngle,
simulateGravity, startingAngle, measurementStdDevs) {}
void SingleJointedArmSim::SetState(wpi::units::radian_t angle,
wpi::units::radians_per_second_t velocity) {
SetState(wpi::math::Vectord<2>{std::clamp(angle, m_minAngle, m_maxAngle), velocity});
SetState(wpi::math::Vectord<2>{std::clamp(angle, m_minAngle, m_maxAngle),
velocity});
}
bool SingleJointedArmSim::WouldHitLowerLimit(wpi::units::radian_t armAngle) const {
bool SingleJointedArmSim::WouldHitLowerLimit(
wpi::units::radian_t armAngle) const {
return armAngle <= m_minAngle;
}
bool SingleJointedArmSim::WouldHitUpperLimit(wpi::units::radian_t armAngle) const {
bool SingleJointedArmSim::WouldHitUpperLimit(
wpi::units::radian_t armAngle) const {
return armAngle >= m_maxAngle;
}
@@ -84,9 +88,9 @@ void SingleJointedArmSim::SetInputVoltage(wpi::units::volt_t voltage) {
ClampInput(wpi::RobotController::GetBatteryVoltage().value());
}
wpi::math::Vectord<2> SingleJointedArmSim::UpdateX(const wpi::math::Vectord<2>& currentXhat,
const wpi::math::Vectord<1>& u,
wpi::units::second_t dt) {
wpi::math::Vectord<2> SingleJointedArmSim::UpdateX(
const wpi::math::Vectord<2>& currentXhat, const wpi::math::Vectord<1>& u,
wpi::units::second_t dt) {
// The torque on the arm is given by τ = F⋅r, where F is the force applied by
// gravity and r the distance from pivot to center of mass. Recall from
// dynamics that the sum of torques for a rigid body is τ = J⋅α, were τ is

View File

@@ -106,8 +106,8 @@ void FieldObject2d::UpdateFromEntry() const {
}
m_poses.resize(size / 3);
for (size_t i = 0; i < size / 3; ++i) {
m_poses[i] =
wpi::math::Pose2d{wpi::units::meter_t{arr[i * 3 + 0]}, wpi::units::meter_t{arr[i * 3 + 1]},
wpi::units::degree_t{arr[i * 3 + 2]}};
m_poses[i] = wpi::math::Pose2d{wpi::units::meter_t{arr[i * 3 + 0]},
wpi::units::meter_t{arr[i * 3 + 1]},
wpi::units::degree_t{arr[i * 3 + 2]}};
}
}

View File

@@ -28,7 +28,8 @@ MechanismLigament2d::MechanismLigament2d(std::string_view name, double length,
void MechanismLigament2d::UpdateEntries(
std::shared_ptr<wpi::nt::NetworkTable> table) {
m_typePub = table->GetStringTopic(".type").PublishEx(
wpi::nt::StringTopic::kTypeString, {{"SmartDashboard", kSmartDashboardType}});
wpi::nt::StringTopic::kTypeString,
{{"SmartDashboard", kSmartDashboardType}});
m_typePub.Set(kSmartDashboardType);
m_colorEntry = table->GetStringTopic("color").GetEntry("");
@@ -45,7 +46,7 @@ void MechanismLigament2d::SetColor(const Color8Bit& color) {
std::scoped_lock lock(m_mutex);
wpi::util::format_to_n_c_str(m_color, sizeof(m_color), "#{:02X}{:02X}{:02X}",
color.red, color.green, color.blue);
color.red, color.green, color.blue);
if (m_colorEntry) {
m_colorEntry.Set(m_color);

View File

@@ -4,10 +4,10 @@
#include "wpi/smartdashboard/MechanismRoot2d.hpp"
#include "wpi/util/Color8Bit.hpp"
#include <memory>
#include "wpi/util/Color8Bit.hpp"
using namespace wpi;
MechanismRoot2d::MechanismRoot2d(std::string_view name, double x, double y,
@@ -21,7 +21,8 @@ void MechanismRoot2d::SetPosition(double x, double y) {
Flush();
}
void MechanismRoot2d::UpdateEntries(std::shared_ptr<wpi::nt::NetworkTable> table) {
void MechanismRoot2d::UpdateEntries(
std::shared_ptr<wpi::nt::NetworkTable> table) {
m_xPub = table->GetDoubleTopic("x").Publish();
m_yPub = table->GetDoubleTopic("y").Publish();
Flush();

View File

@@ -35,7 +35,8 @@ void SendableBuilderImpl::PropertyImpl<Topic>::Update(bool controllable,
}
}
void SendableBuilderImpl::SetTable(std::shared_ptr<wpi::nt::NetworkTable> table) {
void SendableBuilderImpl::SetTable(
std::shared_ptr<wpi::nt::NetworkTable> table) {
m_table = table;
m_controllablePublisher = table->GetBooleanTopic(".controllable").Publish();
m_controllablePublisher.SetDefault(false);
@@ -97,7 +98,8 @@ void SendableBuilderImpl::SetActuator(bool value) {
m_actuator = value;
}
void SendableBuilderImpl::SetUpdateTable(wpi::util::unique_function<void()> func) {
void SendableBuilderImpl::SetUpdateTable(
wpi::util::unique_function<void()> func) {
m_updateTables.emplace_back(std::move(func));
}
@@ -314,7 +316,8 @@ void SendableBuilderImpl::AddSmallPropertyImpl(Topic topic, Getter getter,
void SendableBuilderImpl::AddSmallStringProperty(
std::string_view key,
std::function<std::string_view(wpi::util::SmallVectorImpl<char>& buf)> getter,
std::function<std::string_view(wpi::util::SmallVectorImpl<char>& buf)>
getter,
std::function<void(std::string_view)> setter) {
AddSmallPropertyImpl<char, 128>(m_table->GetStringTopic(key),
std::move(getter), std::move(setter));
@@ -322,7 +325,8 @@ void SendableBuilderImpl::AddSmallStringProperty(
void SendableBuilderImpl::AddSmallBooleanArrayProperty(
std::string_view key,
std::function<std::span<const int>(wpi::util::SmallVectorImpl<int>& buf)> getter,
std::function<std::span<const int>(wpi::util::SmallVectorImpl<int>& buf)>
getter,
std::function<void(std::span<const int>)> setter) {
AddSmallPropertyImpl<int, 16>(m_table->GetBooleanArrayTopic(key),
std::move(getter), std::move(setter));
@@ -330,7 +334,8 @@ void SendableBuilderImpl::AddSmallBooleanArrayProperty(
void SendableBuilderImpl::AddSmallIntegerArrayProperty(
std::string_view key,
std::function<std::span<const int64_t>(wpi::util::SmallVectorImpl<int64_t>& buf)>
std::function<
std::span<const int64_t>(wpi::util::SmallVectorImpl<int64_t>& buf)>
getter,
std::function<void(std::span<const int64_t>)> setter) {
AddSmallPropertyImpl<int64_t, 16>(m_table->GetIntegerArrayTopic(key),
@@ -339,7 +344,8 @@ void SendableBuilderImpl::AddSmallIntegerArrayProperty(
void SendableBuilderImpl::AddSmallFloatArrayProperty(
std::string_view key,
std::function<std::span<const float>(wpi::util::SmallVectorImpl<float>& buf)>
std::function<
std::span<const float>(wpi::util::SmallVectorImpl<float>& buf)>
getter,
std::function<void(std::span<const float>)> setter) {
AddSmallPropertyImpl<float, 16>(m_table->GetFloatArrayTopic(key),
@@ -348,7 +354,8 @@ void SendableBuilderImpl::AddSmallFloatArrayProperty(
void SendableBuilderImpl::AddSmallDoubleArrayProperty(
std::string_view key,
std::function<std::span<const double>(wpi::util::SmallVectorImpl<double>& buf)>
std::function<
std::span<const double>(wpi::util::SmallVectorImpl<double>& buf)>
getter,
std::function<void(std::span<const double>)> setter) {
AddSmallPropertyImpl<double, 16>(m_table->GetDoubleArrayTopic(key),
@@ -357,8 +364,8 @@ void SendableBuilderImpl::AddSmallDoubleArrayProperty(
void SendableBuilderImpl::AddSmallStringArrayProperty(
std::string_view key,
std::function<
std::span<const std::string>(wpi::util::SmallVectorImpl<std::string>& buf)>
std::function<std::span<const std::string>(
wpi::util::SmallVectorImpl<std::string>& buf)>
getter,
std::function<void(std::span<const std::string>)> setter) {
AddSmallPropertyImpl<std::string, 16>(m_table->GetStringArrayTopic(key),

View File

@@ -133,8 +133,8 @@ void Thread::Main() {
freeSpace = UINTMAX_MAX;
}
if (freeSpace < kFreeSpaceThreshold) {
// Delete oldest WPILIB_*.wpilog files (ignore WPILIB_TBD_*.wpilog as we just
// created one)
// Delete oldest WPILIB_*.wpilog files (ignore WPILIB_TBD_*.wpilog as we
// just created one)
std::vector<fs::directory_entry> entries;
for (auto&& entry : fs::directory_iterator{m_logDir, ec}) {
auto stem = entry.path().stem().string();
@@ -158,14 +158,14 @@ void Thread::Main() {
auto size = entry.file_size();
if (fs::remove(entry.path(), ec)) {
WPILIB_ReportWarning("DataLogManager: Deleted {}",
entry.path().string());
entry.path().string());
freeSpace += size;
if (freeSpace >= kFreeSpaceThreshold) {
break;
}
} else {
wpi::util::print(stderr, "DataLogManager: could not delete {}\n",
entry.path().string());
entry.path().string());
}
}
} else if (freeSpace < 2 * kFreeSpaceThreshold) {
@@ -330,7 +330,7 @@ Instance::Instance(std::string_view dir, std::string_view filename,
entry.path().extension() == ".wpilog") {
if (!fs::remove(entry, ec)) {
wpi::util::print(stderr, "DataLogManager: could not delete {}\n",
entry.path().string());
entry.path().string());
}
}
}

View File

@@ -34,7 +34,7 @@ class Watchdog::Impl {
wpi::util::mutex m_mutex;
std::atomic<HAL_NotifierHandle> m_notifier;
wpi::util::priority_queue<Watchdog*, std::vector<Watchdog*>,
DerefGreater<Watchdog*>>
DerefGreater<Watchdog*>>
m_watchdogs;
void UpdateAlarm();
@@ -115,7 +115,7 @@ void Watchdog::Impl::Main() {
watchdog->m_lastTimeoutPrintTime = now;
if (!watchdog->m_suppressTimeoutMessage) {
WPILIB_ReportWarning("Watchdog not fed within {:.6f}s",
watchdog->m_timeout.value());
watchdog->m_timeout.value());
}
}

View File

@@ -71,7 +71,7 @@ class Alert::SendableAlerts : public wpi::nt::NTSendable,
return m_alerts[static_cast<int32_t>(type)];
default:
throw WPILIB_MakeError(wpi::err::InvalidParameter,
"Invalid Alert Type: {}", type);
"Invalid Alert Type: {}", type);
}
}

View File

@@ -29,10 +29,13 @@ struct Instance {
std::shared_ptr<wpi::nt::NetworkTable> table{
wpi::nt::NetworkTableInstance::GetDefault().GetTable(kTableName)};
wpi::nt::StringPublisher typePublisher{table->GetStringTopic(".type").PublishEx(
wpi::nt::StringTopic::kTypeString, {{"SmartDashboard", kSmartDashboardType}})};
wpi::nt::MultiSubscriber tableSubscriber{wpi::nt::NetworkTableInstance::GetDefault(),
{{fmt::format("{}/", table->GetPath())}}};
wpi::nt::StringPublisher typePublisher{
table->GetStringTopic(".type").PublishEx(
wpi::nt::StringTopic::kTypeString,
{{"SmartDashboard", kSmartDashboardType}})};
wpi::nt::MultiSubscriber tableSubscriber{
wpi::nt::NetworkTableInstance::GetDefault(),
{{fmt::format("{}/", table->GetPath())}}};
wpi::nt::NetworkTableListener listener;
};
} // namespace