Replace .to<double>() and .template to<double>() with .value() (#3667)

It's a less verbose way to do the same thing.
This commit is contained in:
Tyler Veness
2021-10-25 08:58:12 -07:00
committed by GitHub
parent 6bc1db44bc
commit 181723e573
134 changed files with 782 additions and 826 deletions

View File

@@ -261,17 +261,17 @@ static DisplayUnits gDisplayUnits = kDisplayMeters;
static double ConvertDisplayLength(units::meter_t v) {
switch (gDisplayUnits) {
case kDisplayFeet:
return v.convert<units::feet>().to<double>();
return v.convert<units::feet>().value();
case kDisplayInches:
return v.convert<units::inches>().to<double>();
return v.convert<units::inches>().value();
case kDisplayMeters:
default:
return v.to<double>();
return v.value();
}
}
static double ConvertDisplayAngle(units::degree_t v) {
return v.to<double>();
return v.value();
}
static bool InputLength(const char* label, units::meter_t* v, double step = 0.0,

View File

@@ -94,9 +94,9 @@ void NTField2DModel::ObjectModel::UpdateNT() {
wpi::SmallVector<double, 9> arr;
for (auto&& pose : m_poses) {
auto& translation = pose.Translation();
arr.push_back(translation.X().to<double>());
arr.push_back(translation.Y().to<double>());
arr.push_back(pose.Rotation().Degrees().to<double>());
arr.push_back(translation.X().value());
arr.push_back(translation.Y().value());
arr.push_back(pose.Rotation().Degrees().value());
}
nt::SetEntryTypeValue(m_entry, nt::Value::MakeDoubleArray(arr));
} else {
@@ -107,13 +107,13 @@ void NTField2DModel::ObjectModel::UpdateNT() {
for (auto&& pose : m_poses) {
auto& translation = pose.Translation();
wpi::support::endian::write64be(
p, wpi::DoubleToBits(translation.X().to<double>()));
p, wpi::DoubleToBits(translation.X().value()));
p += 8;
wpi::support::endian::write64be(
p, wpi::DoubleToBits(translation.Y().to<double>()));
p, wpi::DoubleToBits(translation.Y().value()));
p += 8;
wpi::support::endian::write64be(
p, wpi::DoubleToBits(pose.Rotation().Degrees().to<double>()));
p, wpi::DoubleToBits(pose.Rotation().Degrees().value()));
p += 8;
}
nt::SetEntryTypeValue(m_entry,

View File

@@ -310,20 +310,20 @@ void MecanumControllerCommand::Execute() {
(rearRightSpeedSetpoint - m_prevSpeeds.rearRight) / dt);
auto frontLeftOutput = volt_t(m_frontLeftController->Calculate(
m_currentWheelSpeeds().frontLeft.to<double>(),
frontLeftSpeedSetpoint.to<double>())) +
m_currentWheelSpeeds().frontLeft.value(),
frontLeftSpeedSetpoint.value())) +
frontLeftFeedforward;
auto rearLeftOutput = volt_t(m_rearLeftController->Calculate(
m_currentWheelSpeeds().rearLeft.to<double>(),
rearLeftSpeedSetpoint.to<double>())) +
m_currentWheelSpeeds().rearLeft.value(),
rearLeftSpeedSetpoint.value())) +
rearLeftFeedforward;
auto frontRightOutput = volt_t(m_frontRightController->Calculate(
m_currentWheelSpeeds().frontRight.to<double>(),
frontRightSpeedSetpoint.to<double>())) +
m_currentWheelSpeeds().frontRight.value(),
frontRightSpeedSetpoint.value())) +
frontRightFeedforward;
auto rearRightOutput = volt_t(m_rearRightController->Calculate(
m_currentWheelSpeeds().rearRight.to<double>(),
rearRightSpeedSetpoint.to<double>())) +
m_currentWheelSpeeds().rearRight.value(),
rearRightSpeedSetpoint.value())) +
rearRightFeedforward;
m_outputVolts(frontLeftOutput, rearLeftOutput, frontRightOutput,

View File

@@ -126,15 +126,15 @@ void RamseteCommand::Execute() {
targetWheelSpeeds.right,
(targetWheelSpeeds.right - m_prevSpeeds.right) / dt);
auto leftOutput = volt_t(m_leftController->Calculate(
m_speeds().left.to<double>(),
targetWheelSpeeds.left.to<double>())) +
leftFeedforward;
auto leftOutput =
volt_t(m_leftController->Calculate(m_speeds().left.value(),
targetWheelSpeeds.left.value())) +
leftFeedforward;
auto rightOutput = volt_t(m_rightController->Calculate(
m_speeds().right.to<double>(),
targetWheelSpeeds.right.to<double>())) +
rightFeedforward;
auto rightOutput =
volt_t(m_rightController->Calculate(m_speeds().right.value(),
targetWheelSpeeds.right.value())) +
rightFeedforward;
m_outputVolts(leftOutput, rightOutput);
} else {

View File

@@ -153,7 +153,7 @@ double PIDBase::GetSetpoint() const {
double PIDBase::GetDeltaSetpoint() const {
std::scoped_lock lock(m_thisMutex);
return (m_setpoint - m_prevSetpoint) / m_setpointTimer.Get().to<double>();
return (m_setpoint - m_prevSetpoint) / m_setpointTimer.Get().value();
}
double PIDBase::GetError() const {

View File

@@ -34,7 +34,7 @@ Command::Command(std::string_view name, units::second_t timeout) {
// We use -1.0 to indicate no timeout.
if (timeout < 0_s && timeout != -1_s) {
throw FRC_MakeError(err::ParameterOutOfRange, "timeout {} < 0 s",
timeout.to<double>());
timeout.value());
}
m_timeout = timeout;
@@ -177,7 +177,7 @@ int Command::GetID() const {
void Command::SetTimeout(units::second_t timeout) {
if (timeout < 0_s) {
throw FRC_MakeError(err::ParameterOutOfRange, "timeout {} < 0 s",
timeout.to<double>());
timeout.value());
} else {
m_timeout = timeout;
}

View File

@@ -38,7 +38,7 @@ void CommandGroup::AddSequential(Command* command, units::second_t timeout) {
}
if (timeout < 0_s) {
throw FRC_MakeError(err::ParameterOutOfRange, "timeout {} < 0 s",
timeout.to<double>());
timeout.value());
}
m_commands.emplace_back(command, CommandGroupEntry::kSequence_InSequence,
@@ -82,7 +82,7 @@ void CommandGroup::AddParallel(Command* command, units::second_t timeout) {
}
if (timeout < 0_s) {
throw FRC_MakeError(err::ParameterOutOfRange, "timeout {} < 0 s",
timeout.to<double>());
timeout.value());
}
m_commands.emplace_back(command, CommandGroupEntry::kSequence_BranchChild,

View File

@@ -9,7 +9,7 @@
using namespace frc;
WaitCommand::WaitCommand(units::second_t timeout)
: TimedCommand(fmt::format("Wait({})", timeout.to<double>()), timeout) {}
: TimedCommand(fmt::format("Wait({})", timeout.value()), timeout) {}
WaitCommand::WaitCommand(std::string_view name, units::second_t timeout)
: TimedCommand(name, timeout) {}

View File

@@ -93,7 +93,7 @@ double AnalogEncoder::GetDistancePerRotation() const {
}
double AnalogEncoder::GetDistance() const {
return Get().to<double>() * GetDistancePerRotation();
return Get().value() * GetDistancePerRotation();
}
void AnalogEncoder::Reset() {

View File

@@ -282,7 +282,7 @@ units::second_t Counter::GetPeriod() const {
void Counter::SetMaxPeriod(units::second_t maxPeriod) {
int32_t status = 0;
HAL_SetCounterMaxPeriod(m_counter, maxPeriod.to<double>(), &status);
HAL_SetCounterMaxPeriod(m_counter, maxPeriod.value(), &status);
FRC_CheckErrorStatus(status, "{}", "SetMaxPeriod");
}

View File

@@ -42,7 +42,7 @@ void DMA::SetPause(bool pause) {
void DMA::SetTimedTrigger(units::second_t seconds) {
int32_t status = 0;
HAL_SetDMATimedTrigger(dmaHandle, seconds.to<double>(), &status);
HAL_SetDMATimedTrigger(dmaHandle, seconds.value(), &status);
FRC_CheckErrorStatus(status, "{}", "SetTimedTrigger");
}

View File

@@ -112,7 +112,7 @@ double DutyCycleEncoder::GetDistancePerRotation() const {
}
double DutyCycleEncoder::GetDistance() const {
return Get().to<double>() * GetDistancePerRotation();
return Get().value() * GetDistancePerRotation();
}
int DutyCycleEncoder::GetFrequency() const {

View File

@@ -87,7 +87,7 @@ units::second_t Encoder::GetPeriod() const {
void Encoder::SetMaxPeriod(units::second_t maxPeriod) {
int32_t status = 0;
HAL_SetEncoderMaxPeriod(m_encoder, maxPeriod.to<double>(), &status);
HAL_SetEncoderMaxPeriod(m_encoder, maxPeriod.value(), &status);
FRC_CheckErrorStatus(status, "{}", "SetMaxPeriod");
}

View File

@@ -200,6 +200,5 @@ void IterativeRobotBase::LoopFunc() {
}
void IterativeRobotBase::PrintLoopOverrunMessage() {
FRC_ReportError(err::Error, "Loop time of {:.6f}s overrun",
m_period.to<double>());
FRC_ReportError(err::Error, "Loop time of {:.6f}s overrun", m_period.value());
}

View File

@@ -168,7 +168,7 @@ units::volt_t RobotController::GetBrownoutVoltage() {
void RobotController::SetBrownoutVoltage(units::volt_t brownoutVoltage) {
int32_t status = 0;
HAL_SetBrownoutVoltage(brownoutVoltage.to<double>(), &status);
HAL_SetBrownoutVoltage(brownoutVoltage.value(), &status);
FRC_CheckErrorStatus(status, "{}", "SetBrownoutVoltage");
}

View File

@@ -274,7 +274,7 @@ void SPI::SetAutoTransmitData(wpi::span<const uint8_t> dataToSend,
void SPI::StartAutoRate(units::second_t period) {
int32_t status = 0;
HAL_StartSPIAutoRate(m_port, period.to<double>(), &status);
HAL_StartSPIAutoRate(m_port, period.value(), &status);
FRC_CheckErrorStatus(status, "Port {}", m_port);
}
@@ -307,7 +307,7 @@ int SPI::ReadAutoReceivedData(uint32_t* buffer, int numToRead,
units::second_t timeout) {
int32_t status = 0;
int32_t val = HAL_ReadSPIAutoReceivedData(m_port, buffer, numToRead,
timeout.to<double>(), &status);
timeout.value(), &status);
FRC_CheckErrorStatus(status, "Port {}", m_port);
return val;
}

View File

@@ -124,7 +124,7 @@ int SerialPort::Write(std::string_view buffer) {
void SerialPort::SetTimeout(units::second_t timeout) {
int32_t status = 0;
HAL_SetSerialTimeout(m_portHandle, timeout.to<double>(), &status);
HAL_SetSerialTimeout(m_portHandle, timeout.value(), &status);
FRC_CheckErrorStatus(status, "{}", "SetTimeout");
}

View File

@@ -64,8 +64,8 @@ inline SynchronousInterrupt::WaitResult operator|(
SynchronousInterrupt::WaitResult SynchronousInterrupt::WaitForInterrupt(
units::second_t timeout, bool ignorePrevious) {
int32_t status = 0;
auto result = HAL_WaitForInterrupt(m_handle, timeout.to<double>(),
ignorePrevious, &status);
auto result =
HAL_WaitForInterrupt(m_handle, timeout.value(), ignorePrevious, &status);
auto rising =
((result & 0xFF) != 0) ? WaitResult::kRisingEdge : WaitResult::kTimeout;

View File

@@ -13,8 +13,7 @@
namespace frc {
void Wait(units::second_t seconds) {
std::this_thread::sleep_for(
std::chrono::duration<double>(seconds.to<double>()));
std::this_thread::sleep_for(std::chrono::duration<double>(seconds.value()));
}
units::second_t GetTime() {

View File

@@ -162,7 +162,7 @@ void Ultrasonic::SetEnabled(bool enable) {
void Ultrasonic::InitSendable(wpi::SendableBuilder& builder) {
builder.SetSmartDashboardType("Ultrasonic");
builder.AddDoubleProperty(
"Value", [=] { return units::inch_t{GetRange()}.to<double>(); }, nullptr);
"Value", [=] { return units::inch_t{GetRange()}.value(); }, nullptr);
}
void Ultrasonic::Initialize() {

View File

@@ -80,7 +80,7 @@ void Watchdog::Impl::UpdateAlarm() {
} else {
HAL_UpdateNotifierAlarm(
notifier,
static_cast<uint64_t>(m_watchdogs.top()->m_expirationTime.to<double>() *
static_cast<uint64_t>(m_watchdogs.top()->m_expirationTime.value() *
1e6),
&status);
}
@@ -114,7 +114,7 @@ void Watchdog::Impl::Main() {
watchdog->m_lastTimeoutPrintTime = now;
if (!watchdog->m_suppressTimeoutMessage) {
FRC_ReportError(warn::Warning, "Watchdog not fed within {:.6f}s",
watchdog->m_timeout.to<double>());
watchdog->m_timeout.value());
}
}

View File

@@ -16,9 +16,9 @@ ADXRS450_GyroSim::ADXRS450_GyroSim(const frc::ADXRS450_Gyro& gyro) {
}
void ADXRS450_GyroSim::SetAngle(units::degree_t angle) {
m_simAngle.Set(angle.to<double>());
m_simAngle.Set(angle.value());
}
void ADXRS450_GyroSim::SetRate(units::degrees_per_second_t rate) {
m_simRate.Set(rate.to<double>());
m_simRate.Set(rate.value());
}

View File

@@ -19,7 +19,7 @@ void AnalogEncoderSim::SetPosition(frc::Rotation2d angle) {
}
void AnalogEncoderSim::SetTurns(units::turn_t turns) {
m_positionSim.Set(turns.to<double>());
m_positionSim.Set(turns.value());
}
units::turn_t AnalogEncoderSim::GetTurns() {

View File

@@ -49,7 +49,7 @@ Eigen::Vector<double, 2> DifferentialDrivetrainSim::ClampInput(
void DifferentialDrivetrainSim::SetInputs(units::volt_t leftVoltage,
units::volt_t rightVoltage) {
m_u << leftVoltage.to<double>(), rightVoltage.to<double>();
m_u << leftVoltage.value(), rightVoltage.value();
m_u = ClampInput(m_u);
}
@@ -93,10 +93,10 @@ Pose2d DifferentialDrivetrainSim::GetPose() const {
units::ampere_t DifferentialDrivetrainSim::GetLeftCurrentDraw() const {
auto loadIleft =
m_motor.Current(units::radians_per_second_t(m_x(State::kLeftVelocity) *
m_currentGearing /
m_wheelRadius.to<double>()),
units::volt_t(m_u(0))) *
m_motor.Current(
units::radians_per_second_t(m_x(State::kLeftVelocity) *
m_currentGearing / m_wheelRadius.value()),
units::volt_t(m_u(0))) *
wpi::sgn(m_u(0));
return loadIleft;
@@ -104,10 +104,10 @@ units::ampere_t DifferentialDrivetrainSim::GetLeftCurrentDraw() const {
units::ampere_t DifferentialDrivetrainSim::GetRightCurrentDraw() const {
auto loadIRight =
m_motor.Current(units::radians_per_second_t(m_x(State::kRightVelocity) *
m_currentGearing /
m_wheelRadius.to<double>()),
units::volt_t(m_u(1))) *
m_motor.Current(
units::radians_per_second_t(m_x(State::kRightVelocity) *
m_currentGearing / m_wheelRadius.value()),
units::volt_t(m_u(1))) *
wpi::sgn(m_u(1));
return loadIRight;
@@ -122,9 +122,9 @@ void DifferentialDrivetrainSim::SetState(
}
void DifferentialDrivetrainSim::SetPose(const frc::Pose2d& pose) {
m_x(State::kX) = pose.X().to<double>();
m_x(State::kY) = pose.Y().to<double>();
m_x(State::kHeading) = pose.Rotation().Radians().to<double>();
m_x(State::kX) = pose.X().value();
m_x(State::kY) = pose.Y().value();
m_x(State::kHeading) = pose.Rotation().Radians().value();
m_x(State::kLeftPosition) = 0;
m_x(State::kRightPosition) = 0;
}
@@ -154,7 +154,7 @@ Eigen::Vector<double, 7> DifferentialDrivetrainSim::Dynamics(
xdot(1) = v * std::sin(x(State::kHeading));
xdot(2) =
((x(State::kRightVelocity) - x(State::kLeftVelocity)) / (2.0 * m_rb))
.to<double>();
.value();
xdot.block<4, 1>(3, 0) = A * x.block<4, 1>(3, 0) + B * u;
return xdot;
}

View File

@@ -17,7 +17,7 @@ DutyCycleEncoderSim::DutyCycleEncoderSim(const frc::DutyCycleEncoder& encoder) {
}
void DutyCycleEncoderSim::Set(units::turn_t turns) {
m_simPosition.Set(turns.to<double>());
m_simPosition.Set(turns.value());
}
void DutyCycleEncoderSim::SetDistance(double distance) {

View File

@@ -78,7 +78,7 @@ units::ampere_t ElevatorSim::GetCurrentDraw() const {
}
void ElevatorSim::SetInputVoltage(units::volt_t voltage) {
SetInput(Eigen::Vector<double, 1>{voltage.to<double>()});
SetInput(Eigen::Vector<double, 1>{voltage.value()});
}
Eigen::Vector<double, 2> ElevatorSim::UpdateX(
@@ -93,10 +93,10 @@ Eigen::Vector<double, 2> ElevatorSim::UpdateX(
currentXhat, u, dt);
// Check for collision after updating x-hat.
if (WouldHitLowerLimit(units::meter_t(updatedXhat(0)))) {
return Eigen::Vector<double, 2>{m_minHeight.to<double>(), 0.0};
return Eigen::Vector<double, 2>{m_minHeight.value(), 0.0};
}
if (WouldHitUpperLimit(units::meter_t(updatedXhat(0)))) {
return Eigen::Vector<double, 2>{m_maxHeight.to<double>(), 0.0};
return Eigen::Vector<double, 2>{m_maxHeight.value(), 0.0};
}
return updatedXhat;
}

View File

@@ -38,5 +38,5 @@ units::ampere_t FlywheelSim::GetCurrentDraw() const {
}
void FlywheelSim::SetInputVoltage(units::volt_t voltage) {
SetInput(Eigen::Vector<double, 1>{voltage.to<double>()});
SetInput(Eigen::Vector<double, 1>{voltage.value()});
}

View File

@@ -43,7 +43,7 @@ units::volt_t RoboRioSim::GetVInVoltage() {
}
void RoboRioSim::SetVInVoltage(units::volt_t vInVoltage) {
HALSIM_SetRoboRioVInVoltage(vInVoltage.to<double>());
HALSIM_SetRoboRioVInVoltage(vInVoltage.value());
}
std::unique_ptr<CallbackStore> RoboRioSim::RegisterVInCurrentCallback(
@@ -60,7 +60,7 @@ units::ampere_t RoboRioSim::GetVInCurrent() {
}
void RoboRioSim::SetVInCurrent(units::ampere_t vInCurrent) {
HALSIM_SetRoboRioVInCurrent(vInCurrent.to<double>());
HALSIM_SetRoboRioVInCurrent(vInCurrent.value());
}
std::unique_ptr<CallbackStore> RoboRioSim::RegisterUserVoltage6VCallback(
@@ -77,7 +77,7 @@ units::volt_t RoboRioSim::GetUserVoltage6V() {
}
void RoboRioSim::SetUserVoltage6V(units::volt_t userVoltage6V) {
HALSIM_SetRoboRioUserVoltage6V(userVoltage6V.to<double>());
HALSIM_SetRoboRioUserVoltage6V(userVoltage6V.value());
}
std::unique_ptr<CallbackStore> RoboRioSim::RegisterUserCurrent6VCallback(
@@ -94,7 +94,7 @@ units::ampere_t RoboRioSim::GetUserCurrent6V() {
}
void RoboRioSim::SetUserCurrent6V(units::ampere_t userCurrent6V) {
HALSIM_SetRoboRioUserCurrent6V(userCurrent6V.to<double>());
HALSIM_SetRoboRioUserCurrent6V(userCurrent6V.value());
}
std::unique_ptr<CallbackStore> RoboRioSim::RegisterUserActive6VCallback(
@@ -128,7 +128,7 @@ units::volt_t RoboRioSim::GetUserVoltage5V() {
}
void RoboRioSim::SetUserVoltage5V(units::volt_t userVoltage5V) {
HALSIM_SetRoboRioUserVoltage5V(userVoltage5V.to<double>());
HALSIM_SetRoboRioUserVoltage5V(userVoltage5V.value());
}
std::unique_ptr<CallbackStore> RoboRioSim::RegisterUserCurrent5VCallback(
@@ -145,7 +145,7 @@ units::ampere_t RoboRioSim::GetUserCurrent5V() {
}
void RoboRioSim::SetUserCurrent5V(units::ampere_t userCurrent5V) {
HALSIM_SetRoboRioUserCurrent5V(userCurrent5V.to<double>());
HALSIM_SetRoboRioUserCurrent5V(userCurrent5V.value());
}
std::unique_ptr<CallbackStore> RoboRioSim::RegisterUserActive5VCallback(
@@ -179,7 +179,7 @@ units::volt_t RoboRioSim::GetUserVoltage3V3() {
}
void RoboRioSim::SetUserVoltage3V3(units::volt_t userVoltage3V3) {
HALSIM_SetRoboRioUserVoltage3V3(userVoltage3V3.to<double>());
HALSIM_SetRoboRioUserVoltage3V3(userVoltage3V3.value());
}
std::unique_ptr<CallbackStore> RoboRioSim::RegisterUserCurrent3V3Callback(
@@ -196,7 +196,7 @@ units::ampere_t RoboRioSim::GetUserCurrent3V3() {
}
void RoboRioSim::SetUserCurrent3V3(units::ampere_t userCurrent3V3) {
HALSIM_SetRoboRioUserCurrent3V3(userCurrent3V3.to<double>());
HALSIM_SetRoboRioUserCurrent3V3(userCurrent3V3.value());
}
std::unique_ptr<CallbackStore> RoboRioSim::RegisterUserActive3V3Callback(
@@ -281,7 +281,7 @@ units::volt_t RoboRioSim::GetBrownoutVoltage() {
}
void RoboRioSim::SetBrownoutVoltage(units::volt_t vInVoltage) {
HALSIM_SetRoboRioBrownoutVoltage(vInVoltage.to<double>());
HALSIM_SetRoboRioBrownoutVoltage(vInVoltage.value());
}
void RoboRioSim::ResetData() {

View File

@@ -41,11 +41,11 @@ bool IsTimingPaused() {
}
void StepTiming(units::second_t delta) {
HALSIM_StepTiming(static_cast<uint64_t>(delta.to<double>() * 1e6));
HALSIM_StepTiming(static_cast<uint64_t>(delta.value() * 1e6));
}
void StepTimingAsync(units::second_t delta) {
HALSIM_StepTimingAsync(static_cast<uint64_t>(delta.to<double>() * 1e6));
HALSIM_StepTimingAsync(static_cast<uint64_t>(delta.value() * 1e6));
}
} // namespace frc::sim

View File

@@ -72,7 +72,7 @@ units::ampere_t SingleJointedArmSim::GetCurrentDraw() const {
}
void SingleJointedArmSim::SetInputVoltage(units::volt_t voltage) {
SetInput(Eigen::Vector<double, 1>{voltage.to<double>()});
SetInput(Eigen::Vector<double, 1>{voltage.value()});
}
Eigen::Vector<double, 2> SingleJointedArmSim::UpdateX(
@@ -96,7 +96,7 @@ Eigen::Vector<double, 2> SingleJointedArmSim::UpdateX(
xdot += Eigen::Vector<double, 2>{
0.0, (m_mass * m_r * -9.8 * 3.0 / (m_mass * m_r * m_r) *
std::cos(x(0)))
.template to<double>()};
.value()};
}
return xdot;
},
@@ -104,9 +104,9 @@ Eigen::Vector<double, 2> SingleJointedArmSim::UpdateX(
// Check for collisions.
if (WouldHitLowerLimit(units::radian_t(updatedXhat(0)))) {
return Eigen::Vector<double, 2>{m_minAngle.to<double>(), 0.0};
return Eigen::Vector<double, 2>{m_minAngle.value(), 0.0};
} else if (WouldHitUpperLimit(units::radian_t(updatedXhat(0)))) {
return Eigen::Vector<double, 2>{m_maxAngle.to<double>(), 0.0};
return Eigen::Vector<double, 2>{m_maxAngle.value(), 0.0};
}
return updatedXhat;
}

View File

@@ -20,5 +20,5 @@ void UltrasonicSim::SetRangeValid(bool isValid) {
}
void UltrasonicSim::SetRange(units::meter_t range) {
m_simRange.Set(range.to<double>());
m_simRange.Set(range.value());
}

View File

@@ -87,9 +87,9 @@ void FieldObject2d::UpdateEntry(bool setDefault) {
wpi::SmallVector<double, 9> arr;
for (auto&& pose : m_poses) {
auto& translation = pose.Translation();
arr.push_back(translation.X().to<double>());
arr.push_back(translation.Y().to<double>());
arr.push_back(pose.Rotation().Degrees().to<double>());
arr.push_back(translation.X().value());
arr.push_back(translation.Y().value());
arr.push_back(pose.Rotation().Degrees().value());
}
if (setDefault) {
m_entry.SetDefaultDoubleArray(arr);
@@ -104,13 +104,13 @@ void FieldObject2d::UpdateEntry(bool setDefault) {
for (auto&& pose : m_poses) {
auto& translation = pose.Translation();
wpi::support::endian::write64be(
p, wpi::DoubleToBits(translation.X().to<double>()));
p, wpi::DoubleToBits(translation.X().value()));
p += 8;
wpi::support::endian::write64be(
p, wpi::DoubleToBits(translation.Y().to<double>()));
p, wpi::DoubleToBits(translation.Y().value()));
p += 8;
wpi::support::endian::write64be(
p, wpi::DoubleToBits(pose.Rotation().Degrees().to<double>()));
p, wpi::DoubleToBits(pose.Rotation().Degrees().value()));
p += 8;
}
if (setDefault) {

View File

@@ -14,7 +14,7 @@ MechanismLigament2d::MechanismLigament2d(std::string_view name, double length,
const frc::Color8Bit& color)
: MechanismObject2d(name),
m_length{length},
m_angle{angle.to<double>()},
m_angle{angle.value()},
m_weight{lineWeight} {
SetColor(color);
}
@@ -40,7 +40,7 @@ void MechanismLigament2d::SetColor(const Color8Bit& color) {
void MechanismLigament2d::SetAngle(units::degree_t angle) {
std::scoped_lock lock(m_mutex);
m_angle = angle.to<double>();
m_angle = angle.value();
Flush();
}

View File

@@ -27,8 +27,8 @@ class DMASample : public HAL_DMASample {
DMAReadStatus Update(const DMA* dma, units::second_t timeout,
int32_t* remaining, int32_t* status) {
return static_cast<DMAReadStatus>(HAL_ReadDMA(
dma->dmaHandle, this, timeout.to<double>(), remaining, status));
return static_cast<DMAReadStatus>(
HAL_ReadDMA(dma->dmaHandle, this, timeout.value(), remaining, status));
}
uint64_t GetTime() const { return timeStamp; }

View File

@@ -12,15 +12,15 @@ TEST(UltrasonicTest, SimDevices) {
Ultrasonic ultrasonic{0, 1};
sim::UltrasonicSim sim{ultrasonic};
EXPECT_EQ(0, ultrasonic.GetRange().to<double>());
EXPECT_EQ(0, ultrasonic.GetRange().value());
EXPECT_TRUE(ultrasonic.IsRangeValid());
sim.SetRange(units::meter_t{35.04});
EXPECT_EQ(35.04, ultrasonic.GetRange().to<double>());
EXPECT_EQ(35.04, ultrasonic.GetRange().value());
sim.SetRangeValid(false);
EXPECT_FALSE(ultrasonic.IsRangeValid());
EXPECT_EQ(0, ultrasonic.GetRange().to<double>());
EXPECT_EQ(0, ultrasonic.GetRange().value());
}
} // namespace frc

View File

@@ -25,8 +25,8 @@ TEST(ADXRS450GyroSimTest, SetAttributes) {
sim.SetAngle(TEST_ANGLE);
sim.SetRate(TEST_RATE);
EXPECT_EQ(TEST_ANGLE.to<double>(), gyro.GetAngle());
EXPECT_EQ(TEST_RATE.to<double>(), gyro.GetRate());
EXPECT_EQ(TEST_ANGLE.value(), gyro.GetAngle());
EXPECT_EQ(TEST_RATE.value(), gyro.GetRate());
gyro.Reset();
EXPECT_EQ(0, gyro.GetAngle());

View File

@@ -20,8 +20,8 @@ TEST(AnalogEncoderSimTest, Basic) {
frc::sim::AnalogEncoderSim encoderSim{encoder};
encoderSim.SetPosition(180_deg);
EXPECT_NEAR(encoder.Get().to<double>(), 0.5, 1E-8);
EXPECT_NEAR(encoderSim.GetTurns().to<double>(), 0.5, 1E-8);
EXPECT_NEAR(encoderSim.GetPosition().Radians().to<double>(), wpi::numbers::pi,
EXPECT_NEAR(encoder.Get().value(), 0.5, 1E-8);
EXPECT_NEAR(encoderSim.GetTurns().value(), 0.5, 1E-8);
EXPECT_NEAR(encoderSim.GetPosition().Radians().value(), wpi::numbers::pi,
1E-8);
}

View File

@@ -43,7 +43,7 @@ TEST(AnalogGyroSimTest, SetAngle) {
sim.SetAngle(kTestAngle);
EXPECT_EQ(kTestAngle, sim.GetAngle());
EXPECT_EQ(kTestAngle, gyro.GetAngle());
EXPECT_EQ(-kTestAngle, gyro.GetRotation2d().Degrees().to<double>());
EXPECT_EQ(-kTestAngle, gyro.GetRotation2d().Degrees().value());
EXPECT_TRUE(callback.WasTriggered());
EXPECT_EQ(kTestAngle, callback.GetLastValue());
}

View File

@@ -43,13 +43,13 @@ TEST(DifferentialDriveSimTest, Convergence) {
frc::Pose2d(), {}, frc::Pose2d(2_m, 2_m, 0_rad), config);
// NOLINTNEXTLINE
for (double t = 0; t < trajectory.TotalTime().to<double>(); t += 0.02) {
for (double t = 0; t < trajectory.TotalTime().value(); t += 0.02) {
auto state = trajectory.Sample(20_ms);
auto ramseteOut = ramsete.Calculate(sim.GetPose(), state);
auto [l, r] = kinematics.ToWheelSpeeds(ramseteOut);
auto voltages = feedforward.Calculate(
Eigen::Vector<double, 2>{l.to<double>(), r.to<double>()});
auto voltages =
feedforward.Calculate(Eigen::Vector<double, 2>{l.value(), r.value()});
// Sim periodic code.
sim.SetInputs(units::volt_t(voltages(0, 0)), units::volt_t(voltages(1, 0)));
@@ -65,10 +65,9 @@ TEST(DifferentialDriveSimTest, Convergence) {
// 2 inch tolerance is OK since our ground truth is an approximation of the
// ODE solution using RK4 anyway
EXPECT_NEAR(groundTruthX(0, 0), sim.GetPose().X().to<double>(), 0.05);
EXPECT_NEAR(groundTruthX(1, 0), sim.GetPose().Y().to<double>(), 0.05);
EXPECT_NEAR(groundTruthX(2, 0), sim.GetHeading().Radians().to<double>(),
0.01);
EXPECT_NEAR(groundTruthX(0, 0), sim.GetPose().X().value(), 0.05);
EXPECT_NEAR(groundTruthX(1, 0), sim.GetPose().Y().value(), 0.05);
EXPECT_NEAR(groundTruthX(2, 0), sim.GetHeading().Radians().value(), 0.01);
}
TEST(DifferentialDriveSimTest, Current) {

View File

@@ -41,7 +41,7 @@ TEST(ElevatorSimTest, StateSpaceSim) {
encoderSim.SetDistance(y(0));
}
EXPECT_NEAR(controller.GetSetpoint(), sim.GetPosition().to<double>(), 0.2);
EXPECT_NEAR(controller.GetSetpoint(), sim.GetPosition().value(), 0.2);
}
TEST(ElevatorSimTest, MinMax) {

View File

@@ -91,7 +91,7 @@ TEST(EncoderSimTest, Period) {
auto cb = sim.RegisterPeriodCallback(callback.GetCallback(), false);
sim.SetPeriod(123.456);
EXPECT_EQ(123.456, sim.GetPeriod());
EXPECT_EQ(123.456, encoder.GetPeriod().to<double>());
EXPECT_EQ(123.456, encoder.GetPeriod().value());
EXPECT_EQ(kDefaultDistancePerPulse / 123.456, encoder.GetRate());
EXPECT_TRUE(callback.WasTriggered());

View File

@@ -50,13 +50,13 @@ TEST(RoboRioSimTest, SetVin) {
RoboRioSim::SetVInVoltage(units::volt_t{kTestVoltage});
EXPECT_TRUE(voltageCallback.WasTriggered());
EXPECT_EQ(kTestVoltage, voltageCallback.GetLastValue());
EXPECT_EQ(kTestVoltage, RoboRioSim::GetVInVoltage().to<double>());
EXPECT_EQ(kTestVoltage, RoboRioSim::GetVInVoltage().value());
EXPECT_EQ(kTestVoltage, RobotController::GetInputVoltage());
RoboRioSim::SetVInCurrent(units::ampere_t{kTestCurrent});
EXPECT_TRUE(currentCallback.WasTriggered());
EXPECT_EQ(kTestCurrent, currentCallback.GetLastValue());
EXPECT_EQ(kTestCurrent, RoboRioSim::GetVInCurrent().to<double>());
EXPECT_EQ(kTestCurrent, RoboRioSim::GetVInCurrent().value());
EXPECT_EQ(kTestCurrent, RobotController::GetInputCurrent());
}
@@ -71,8 +71,8 @@ TEST(RoboRioSimTest, SetBrownout) {
RoboRioSim::SetBrownoutVoltage(units::volt_t{kTestVoltage});
EXPECT_TRUE(voltageCallback.WasTriggered());
EXPECT_EQ(kTestVoltage, voltageCallback.GetLastValue());
EXPECT_EQ(kTestVoltage, RoboRioSim::GetBrownoutVoltage().to<double>());
EXPECT_EQ(kTestVoltage, RobotController::GetBrownoutVoltage().to<double>());
EXPECT_EQ(kTestVoltage, RoboRioSim::GetBrownoutVoltage().value());
EXPECT_EQ(kTestVoltage, RobotController::GetBrownoutVoltage().value());
}
TEST(RoboRioSimTest, Set6V) {
@@ -97,13 +97,13 @@ TEST(RoboRioSimTest, Set6V) {
RoboRioSim::SetUserVoltage6V(units::volt_t{kTestVoltage});
EXPECT_TRUE(voltageCallback.WasTriggered());
EXPECT_EQ(kTestVoltage, voltageCallback.GetLastValue());
EXPECT_EQ(kTestVoltage, RoboRioSim::GetUserVoltage6V().to<double>());
EXPECT_EQ(kTestVoltage, RoboRioSim::GetUserVoltage6V().value());
EXPECT_EQ(kTestVoltage, RobotController::GetVoltage6V());
RoboRioSim::SetUserCurrent6V(units::ampere_t{kTestCurrent});
EXPECT_TRUE(currentCallback.WasTriggered());
EXPECT_EQ(kTestCurrent, currentCallback.GetLastValue());
EXPECT_EQ(kTestCurrent, RoboRioSim::GetUserCurrent6V().to<double>());
EXPECT_EQ(kTestCurrent, RoboRioSim::GetUserCurrent6V().value());
EXPECT_EQ(kTestCurrent, RobotController::GetCurrent6V());
RoboRioSim::SetUserActive6V(false);
@@ -141,13 +141,13 @@ TEST(RoboRioSimTest, Set5V) {
RoboRioSim::SetUserVoltage5V(units::volt_t{kTestVoltage});
EXPECT_TRUE(voltageCallback.WasTriggered());
EXPECT_EQ(kTestVoltage, voltageCallback.GetLastValue());
EXPECT_EQ(kTestVoltage, RoboRioSim::GetUserVoltage5V().to<double>());
EXPECT_EQ(kTestVoltage, RoboRioSim::GetUserVoltage5V().value());
EXPECT_EQ(kTestVoltage, RobotController::GetVoltage5V());
RoboRioSim::SetUserCurrent5V(units::ampere_t{kTestCurrent});
EXPECT_TRUE(currentCallback.WasTriggered());
EXPECT_EQ(kTestCurrent, currentCallback.GetLastValue());
EXPECT_EQ(kTestCurrent, RoboRioSim::GetUserCurrent5V().to<double>());
EXPECT_EQ(kTestCurrent, RoboRioSim::GetUserCurrent5V().value());
EXPECT_EQ(kTestCurrent, RobotController::GetCurrent5V());
RoboRioSim::SetUserActive5V(false);
@@ -185,13 +185,13 @@ TEST(RoboRioSimTest, Set3V3) {
RoboRioSim::SetUserVoltage3V3(units::volt_t{kTestVoltage});
EXPECT_TRUE(voltageCallback.WasTriggered());
EXPECT_EQ(kTestVoltage, voltageCallback.GetLastValue());
EXPECT_EQ(kTestVoltage, RoboRioSim::GetUserVoltage3V3().to<double>());
EXPECT_EQ(kTestVoltage, RoboRioSim::GetUserVoltage3V3().value());
EXPECT_EQ(kTestVoltage, RobotController::GetVoltage3V3());
RoboRioSim::SetUserCurrent3V3(units::ampere_t{kTestCurrent});
EXPECT_TRUE(currentCallback.WasTriggered());
EXPECT_EQ(kTestCurrent, currentCallback.GetLastValue());
EXPECT_EQ(kTestCurrent, RoboRioSim::GetUserCurrent3V3().to<double>());
EXPECT_EQ(kTestCurrent, RoboRioSim::GetUserCurrent3V3().value());
EXPECT_EQ(kTestCurrent, RobotController::GetCurrent3V3());
RoboRioSim::SetUserActive3V3(false);

View File

@@ -18,5 +18,5 @@ TEST(SingleJointedArmTest, Disabled) {
}
// The arm should swing down.
EXPECT_NEAR(sim.GetAngle().to<double>(), -wpi::numbers::pi / 2, 0.01);
EXPECT_NEAR(sim.GetAngle().value(), -wpi::numbers::pi / 2, 0.01);
}

View File

@@ -51,7 +51,7 @@ TEST(StateSpaceSimTest, FlywheelSim) {
sim.SetInput(Eigen::Vector<double, 1>{
motor.Get() * frc::RobotController::GetInputVoltage()});
sim.Update(20_ms);
encoderSim.SetRate(sim.GetAngularVelocity().to<double>());
encoderSim.SetRate(sim.GetAngularVelocity().value());
}
ASSERT_TRUE(std::abs(200 - encoder.GetRate()) < 0.1);

View File

@@ -16,7 +16,7 @@ ArmSubsystem::ArmSubsystem()
m_motor(kMotorPort),
m_encoder(kEncoderPorts[0], kEncoderPorts[1]),
m_feedforward(kS, kCos, kV, kA) {
m_encoder.SetDistancePerPulse(kEncoderDistancePerPulse.to<double>());
m_encoder.SetDistancePerPulse(kEncoderDistancePerPulse.value());
// Start arm in neutral position
SetGoal(State{kArmOffset, 0_rad_per_s});
}

View File

@@ -23,5 +23,5 @@ void ArmSubsystem::UseState(State setpoint) {
m_feedforward.Calculate(setpoint.position, setpoint.velocity);
// Add the feedforward to the PID output to get the motor output
m_motor.SetSetpoint(ExampleSmartMotorController::PIDMode::kPosition,
setpoint.position.to<double>(), feedforward / 12_V);
setpoint.position.value(), feedforward / 12_V);
}

View File

@@ -94,7 +94,7 @@ class Robot : public frc::TimedRobot {
// Finally, we set our simulated encoder's readings and simulated battery
// voltage
m_encoderSim.SetDistance(m_armSim.GetAngle().to<double>());
m_encoderSim.SetDistance(m_armSim.GetAngle().value());
// SimBattery estimates loaded battery voltages
frc::sim::RoboRioSim::SetVInVoltage(
frc::sim::BatterySim::Calculate({m_armSim.GetCurrentDraw()}));
@@ -108,7 +108,7 @@ class Robot : public frc::TimedRobot {
// Here, we run PID control like normal, with a constant setpoint of 75
// degrees.
double pidOutput = m_controller.Calculate(
m_encoder.GetDistance(), (units::radian_t(75_deg)).to<double>());
m_encoder.GetDistance(), (units::radian_t(75_deg)).value());
m_motor.SetVoltage(units::volt_t(pidOutput));
} else {
// Otherwise, we disable the motor.

View File

@@ -8,9 +8,9 @@ void Drivetrain::SetSpeeds(const frc::DifferentialDriveWheelSpeeds& speeds) {
const auto leftFeedforward = m_feedforward.Calculate(speeds.left);
const auto rightFeedforward = m_feedforward.Calculate(speeds.right);
const double leftOutput = m_leftPIDController.Calculate(
m_leftEncoder.GetRate(), speeds.left.to<double>());
m_leftEncoder.GetRate(), speeds.left.value());
const double rightOutput = m_rightPIDController.Calculate(
m_rightEncoder.GetRate(), speeds.right.to<double>());
m_rightEncoder.GetRate(), speeds.right.value());
m_leftGroup.SetVoltage(units::volt_t{leftOutput} + leftFeedforward);
m_rightGroup.SetVoltage(units::volt_t{rightOutput} + rightFeedforward);

View File

@@ -12,9 +12,9 @@ void Drivetrain::SetSpeeds(const frc::DifferentialDriveWheelSpeeds& speeds) {
const auto leftFeedforward = m_feedforward.Calculate(speeds.left);
const auto rightFeedforward = m_feedforward.Calculate(speeds.right);
const double leftOutput = m_leftPIDController.Calculate(
m_leftEncoder.GetRate(), speeds.left.to<double>());
m_leftEncoder.GetRate(), speeds.left.value());
const double rightOutput = m_rightPIDController.Calculate(
m_rightEncoder.GetRate(), speeds.right.to<double>());
m_rightEncoder.GetRate(), speeds.right.value());
m_leftGroup.SetVoltage(units::volt_t{leftOutput} + leftFeedforward);
m_rightGroup.SetVoltage(units::volt_t{rightOutput} + rightFeedforward);

View File

@@ -34,9 +34,9 @@ class Drivetrain {
// distance traveled for one rotation of the wheel divided by the encoder
// resolution.
m_leftEncoder.SetDistancePerPulse(
2 * wpi::numbers::pi * kWheelRadius.to<double>() / kEncoderResolution);
2 * wpi::numbers::pi * kWheelRadius.value() / kEncoderResolution);
m_rightEncoder.SetDistancePerPulse(
2 * wpi::numbers::pi * kWheelRadius.to<double>() / kEncoderResolution);
2 * wpi::numbers::pi * kWheelRadius.value() / kEncoderResolution);
m_leftEncoder.Reset();
m_rightEncoder.Reset();

View File

@@ -37,10 +37,10 @@ void DriveSubsystem::SetDriveStates(
frc::TrapezoidProfile<units::meters>::State left,
frc::TrapezoidProfile<units::meters>::State right) {
m_leftLeader.SetSetpoint(ExampleSmartMotorController::PIDMode::kPosition,
left.position.to<double>(),
left.position.value(),
m_feedforward.Calculate(left.velocity) / 12_V);
m_rightLeader.SetSetpoint(ExampleSmartMotorController::PIDMode::kPosition,
right.position.to<double>(),
right.position.value(),
m_feedforward.Calculate(right.velocity) / 12_V);
}

View File

@@ -31,7 +31,7 @@ class Robot : public frc::TimedRobot {
frc::SmartDashboard::PutBoolean("Connected", connected);
frc::SmartDashboard::PutNumber("Frequency", frequency);
frc::SmartDashboard::PutNumber("Output", output.to<double>());
frc::SmartDashboard::PutNumber("Output", output.value());
frc::SmartDashboard::PutNumber("Distance", distance);
}
};

View File

@@ -46,7 +46,7 @@ class Robot : public frc::TimedRobot {
// distance per pulse = (distance per revolution) / (pulses per revolution)
// = (Pi * D) / ppr
static constexpr double kArmEncoderDistPerPulse =
2.0 * wpi::numbers::pi * kElevatorDrumRadius.to<double>() / 4096.0;
2.0 * wpi::numbers::pi * kElevatorDrumRadius.value() / 4096.0;
// This gearbox represents a gearbox containing 4 Vex 775pro motors.
frc::DCMotor m_elevatorGearbox = frc::DCMotor::Vex775Pro(4);
@@ -73,7 +73,7 @@ class Robot : public frc::TimedRobot {
m_mech2d.GetRoot("Elevator Root", 10, 0);
frc::MechanismLigament2d* m_elevatorMech2d =
m_elevatorRoot->Append<frc::MechanismLigament2d>(
"Elevator", units::inch_t(m_elevatorSim.GetPosition()).to<double>(),
"Elevator", units::inch_t(m_elevatorSim.GetPosition()).value(),
90_deg);
public:
@@ -95,21 +95,21 @@ class Robot : public frc::TimedRobot {
// Finally, we set our simulated encoder's readings and simulated battery
// voltage
m_encoderSim.SetDistance(m_elevatorSim.GetPosition().to<double>());
m_encoderSim.SetDistance(m_elevatorSim.GetPosition().value());
// SimBattery estimates loaded battery voltages
frc::sim::RoboRioSim::SetVInVoltage(
frc::sim::BatterySim::Calculate({m_elevatorSim.GetCurrentDraw()}));
// Update the Elevator length based on the simulated elevator height
m_elevatorMech2d->SetLength(
units::inch_t(m_elevatorSim.GetPosition()).to<double>());
units::inch_t(m_elevatorSim.GetPosition()).value());
}
void TeleopPeriodic() override {
if (m_joystick.GetTrigger()) {
// Here, we run PID control like normal, with a constant setpoint of 30in.
double pidOutput = m_controller.Calculate(
m_encoder.GetDistance(), units::meter_t(30_in).to<double>());
double pidOutput = m_controller.Calculate(m_encoder.GetDistance(),
units::meter_t(30_in).value());
m_motor.SetVoltage(units::volt_t(pidOutput));
} else {
// Otherwise, we disable the motor.

View File

@@ -43,7 +43,7 @@ class Robot : public frc::TimedRobot {
// Send setpoint to offboard controller PID
m_motor.SetSetpoint(ExampleSmartMotorController::PIDMode::kPosition,
m_setpoint.position.to<double>(),
m_setpoint.position.value(),
m_feedforward.Calculate(m_setpoint.velocity) / 12_V);
}

View File

@@ -16,9 +16,9 @@ ShooterSubsystem::ShooterSubsystem()
m_feederMotor(kFeederMotorPort),
m_shooterEncoder(kEncoderPorts[0], kEncoderPorts[1]),
m_shooterFeedforward(kS, kV) {
m_controller.SetTolerance(kShooterToleranceRPS.to<double>());
m_controller.SetTolerance(kShooterToleranceRPS.value());
m_shooterEncoder.SetDistancePerPulse(kEncoderDistancePerPulse);
SetSetpoint(kShooterTargetRPS.to<double>());
SetSetpoint(kShooterTargetRPS.value());
}
void ShooterSubsystem::UseOutput(double output, double setpoint) {

View File

@@ -25,9 +25,9 @@ Drivetrain::Drivetrain() {
m_rightEncoder.SetDistancePerPulse(0.042);
#else
// Circumference = diameter * pi. 360 tick simulated encoders.
m_leftEncoder.SetDistancePerPulse(units::foot_t{4_in}.to<double>() *
m_leftEncoder.SetDistancePerPulse(units::foot_t{4_in}.value() *
wpi::numbers::pi / 360.0);
m_rightEncoder.SetDistancePerPulse(units::foot_t{4_in}.to<double>() *
m_rightEncoder.SetDistancePerPulse(units::foot_t{4_in}.value() *
wpi::numbers::pi / 360.0);
#endif
SetName("Drivetrain");

View File

@@ -12,9 +12,9 @@ TurnToAngle::TurnToAngle(units::degree_t target, DriveSubsystem* drive)
: CommandHelper(
frc2::PIDController(kTurnP, kTurnI, kTurnD),
// Close loop on heading
[drive] { return drive->GetHeading().to<double>(); },
[drive] { return drive->GetHeading().value(); },
// Set reference to target
target.to<double>(),
target.value(),
// Pipe output to turn robot
[drive](double output) { drive->ArcadeDrive(0, output); },
// Require the drive
@@ -24,8 +24,7 @@ TurnToAngle::TurnToAngle(units::degree_t target, DriveSubsystem* drive)
// Set the controller tolerance - the delta tolerance ensures the robot is
// stationary at the setpoint before it is considered as having reached the
// reference
m_controller.SetTolerance(kTurnTolerance.to<double>(),
kTurnRateTolerance.to<double>());
m_controller.SetTolerance(kTurnTolerance.value(), kTurnRateTolerance.value());
AddRequirements({drive});
}

View File

@@ -22,13 +22,13 @@ void Drivetrain::SetSpeeds(const frc::MecanumDriveWheelSpeeds& wheelSpeeds) {
m_feedforward.Calculate(wheelSpeeds.rearRight);
const double frontLeftOutput = m_frontLeftPIDController.Calculate(
m_frontLeftEncoder.GetRate(), wheelSpeeds.frontLeft.to<double>());
m_frontLeftEncoder.GetRate(), wheelSpeeds.frontLeft.value());
const double frontRightOutput = m_frontRightPIDController.Calculate(
m_frontRightEncoder.GetRate(), wheelSpeeds.frontRight.to<double>());
m_frontRightEncoder.GetRate(), wheelSpeeds.frontRight.value());
const double backLeftOutput = m_backLeftPIDController.Calculate(
m_backLeftEncoder.GetRate(), wheelSpeeds.rearLeft.to<double>());
m_backLeftEncoder.GetRate(), wheelSpeeds.rearLeft.value());
const double backRightOutput = m_backRightPIDController.Calculate(
m_backRightEncoder.GetRate(), wheelSpeeds.rearRight.to<double>());
m_backRightEncoder.GetRate(), wheelSpeeds.rearRight.value());
m_frontLeftMotor.SetVoltage(units::volt_t{frontLeftOutput} +
frontLeftFeedforward);

View File

@@ -18,15 +18,14 @@ frc::MecanumDriveWheelSpeeds Drivetrain::GetCurrentState() const {
void Drivetrain::SetSpeeds(const frc::MecanumDriveWheelSpeeds& wheelSpeeds) {
std::function<void(units::meters_per_second_t, const frc::Encoder&,
frc2::PIDController&, frc::PWMSparkMax&)>
calcAndSetSpeeds =
[&m_feedforward = m_feedforward](units::meters_per_second_t speed,
const auto& encoder,
auto& controller, auto& motor) {
auto feedforward = m_feedforward.Calculate(speed);
double output =
controller.Calculate(encoder.GetRate(), speed.to<double>());
motor.SetVoltage(units::volt_t{output} + feedforward);
};
calcAndSetSpeeds = [&m_feedforward = m_feedforward](
units::meters_per_second_t speed,
const auto& encoder, auto& controller,
auto& motor) {
auto feedforward = m_feedforward.Calculate(speed);
double output = controller.Calculate(encoder.GetRate(), speed.value());
motor.SetVoltage(units::volt_t{output} + feedforward);
};
calcAndSetSpeeds(wheelSpeeds.frontLeft, m_frontLeftEncoder,
m_frontLeftPIDController, m_frontLeftMotor);

View File

@@ -8,9 +8,9 @@ void Drivetrain::SetSpeeds(const frc::DifferentialDriveWheelSpeeds& speeds) {
const auto leftFeedforward = m_feedforward.Calculate(speeds.left);
const auto rightFeedforward = m_feedforward.Calculate(speeds.right);
const double leftOutput = m_leftPIDController.Calculate(
m_leftEncoder.GetRate(), speeds.left.to<double>());
m_leftEncoder.GetRate(), speeds.left.value());
const double rightOutput = m_rightPIDController.Calculate(
m_rightEncoder.GetRate(), speeds.right.to<double>());
m_rightEncoder.GetRate(), speeds.right.value());
m_leftGroup.SetVoltage(units::volt_t{leftOutput} + leftFeedforward);
m_rightGroup.SetVoltage(units::volt_t{rightOutput} + rightFeedforward);

View File

@@ -20,10 +20,10 @@ Drivetrain::Drivetrain() {
// gearbox is constructed, you might have to invert the left side instead.
m_rightMotor.SetInverted(true);
m_leftEncoder.SetDistancePerPulse(
wpi::numbers::pi * kWheelDiameter.to<double>() / kCountsPerRevolution);
m_rightEncoder.SetDistancePerPulse(
wpi::numbers::pi * kWheelDiameter.to<double>() / kCountsPerRevolution);
m_leftEncoder.SetDistancePerPulse(wpi::numbers::pi * kWheelDiameter.value() /
kCountsPerRevolution);
m_rightEncoder.SetDistancePerPulse(wpi::numbers::pi * kWheelDiameter.value() /
kCountsPerRevolution);
ResetEncoders();
}

View File

@@ -10,9 +10,9 @@ void Drivetrain::SetSpeeds(const frc::DifferentialDriveWheelSpeeds& speeds) {
auto leftFeedforward = m_feedforward.Calculate(speeds.left);
auto rightFeedforward = m_feedforward.Calculate(speeds.right);
double leftOutput = m_leftPIDController.Calculate(m_leftEncoder.GetRate(),
speeds.left.to<double>());
double rightOutput = m_rightPIDController.Calculate(
m_rightEncoder.GetRate(), speeds.right.to<double>());
speeds.left.value());
double rightOutput = m_rightPIDController.Calculate(m_rightEncoder.GetRate(),
speeds.right.value());
m_leftGroup.SetVoltage(units::volt_t{leftOutput} + leftFeedforward);
m_rightGroup.SetVoltage(units::volt_t{rightOutput} + rightFeedforward);
@@ -47,16 +47,12 @@ void Drivetrain::SimulationPeriodic() {
frc::RobotController::GetInputVoltage());
m_drivetrainSimulator.Update(20_ms);
m_leftEncoderSim.SetDistance(
m_drivetrainSimulator.GetLeftPosition().to<double>());
m_leftEncoderSim.SetRate(
m_drivetrainSimulator.GetLeftVelocity().to<double>());
m_leftEncoderSim.SetDistance(m_drivetrainSimulator.GetLeftPosition().value());
m_leftEncoderSim.SetRate(m_drivetrainSimulator.GetLeftVelocity().value());
m_rightEncoderSim.SetDistance(
m_drivetrainSimulator.GetRightPosition().to<double>());
m_rightEncoderSim.SetRate(
m_drivetrainSimulator.GetRightVelocity().to<double>());
m_gyroSim.SetAngle(
-m_drivetrainSimulator.GetHeading().Degrees().to<double>());
m_drivetrainSimulator.GetRightPosition().value());
m_rightEncoderSim.SetRate(m_drivetrainSimulator.GetRightVelocity().value());
m_gyroSim.SetAngle(-m_drivetrainSimulator.GetHeading().Degrees().value());
}
void Drivetrain::Periodic() {

View File

@@ -122,9 +122,9 @@ class Robot : public frc::TimedRobot {
m_lastProfiledReference))
.Calculate(20_ms);
m_loop.SetNextR(Eigen::Vector<double, 2>{
m_lastProfiledReference.position.to<double>(),
m_lastProfiledReference.velocity.to<double>()});
m_loop.SetNextR(
Eigen::Vector<double, 2>{m_lastProfiledReference.position.value(),
m_lastProfiledReference.velocity.value()});
// Correct our Kalman filter's state vector estimate with encoder data.
m_loop.Correct(Eigen::Vector<double, 1>{m_encoder.GetDistance()});

View File

@@ -46,14 +46,11 @@ void DriveSubsystem::SimulationPeriodic() {
frc::RobotController::GetInputVoltage());
m_drivetrainSimulator.Update(20_ms);
m_leftEncoderSim.SetDistance(
m_drivetrainSimulator.GetLeftPosition().to<double>());
m_leftEncoderSim.SetRate(
m_drivetrainSimulator.GetLeftVelocity().to<double>());
m_leftEncoderSim.SetDistance(m_drivetrainSimulator.GetLeftPosition().value());
m_leftEncoderSim.SetRate(m_drivetrainSimulator.GetLeftVelocity().value());
m_rightEncoderSim.SetDistance(
m_drivetrainSimulator.GetRightPosition().to<double>());
m_rightEncoderSim.SetRate(
m_drivetrainSimulator.GetRightVelocity().to<double>());
m_drivetrainSimulator.GetRightPosition().value());
m_rightEncoderSim.SetRate(m_drivetrainSimulator.GetRightVelocity().value());
m_gyroSim.SetAngle(-m_drivetrainSimulator.GetHeading().Degrees());
}

View File

@@ -43,7 +43,7 @@ constexpr int kEncoderCPR = 1024;
constexpr auto kWheelDiameter = 6_in;
constexpr double kEncoderDistancePerPulse =
// Assumes the encoders are directly mounted on the wheel shafts
(kWheelDiameter.to<double>() * wpi::numbers::pi) /
(kWheelDiameter.value() * wpi::numbers::pi) /
static_cast<double>(kEncoderCPR);
// These are example values only - DO NOT USE THESE FOR YOUR OWN ROBOT!

View File

@@ -90,8 +90,8 @@ class Robot : public frc::TimedRobot {
public:
void RobotInit() override {
// Circumference = pi * d, so distance per click = pi * d / counts
m_encoder.SetDistancePerPulse(2.0 * wpi::numbers::pi *
kDrumRadius.to<double>() / 4096.0);
m_encoder.SetDistancePerPulse(2.0 * wpi::numbers::pi * kDrumRadius.value() /
4096.0);
}
void TeleopInit() override {
@@ -119,9 +119,9 @@ class Robot : public frc::TimedRobot {
m_lastProfiledReference))
.Calculate(20_ms);
m_loop.SetNextR(Eigen::Vector<double, 2>{
m_lastProfiledReference.position.to<double>(),
m_lastProfiledReference.velocity.to<double>()});
m_loop.SetNextR(
Eigen::Vector<double, 2>{m_lastProfiledReference.position.value(),
m_lastProfiledReference.velocity.value()});
// Correct our Kalman filter's state vector estimate with encoder data.
m_loop.Correct(Eigen::Vector<double, 1>{m_encoder.GetDistance()});

View File

@@ -93,7 +93,7 @@ class Robot : public frc::TimedRobot {
// setpoint of a PID controller.
if (m_joystick.GetRightBumper()) {
// We pressed the bumper, so let's set our next reference
m_loop.SetNextR(Eigen::Vector<double, 1>{kSpinup.to<double>()});
m_loop.SetNextR(Eigen::Vector<double, 1>{kSpinup.value()});
} else {
// We released the bumper, so let's spin down
m_loop.SetNextR(Eigen::Vector<double, 1>{0.0});

View File

@@ -94,7 +94,7 @@ class Robot : public frc::TimedRobot {
// setpoint of a PID controller.
if (m_joystick.GetRightBumper()) {
// We pressed the bumper, so let's set our next reference
m_loop.SetNextR(Eigen::Vector<double, 1>{kSpinup.to<double>()});
m_loop.SetNextR(Eigen::Vector<double, 1>{kSpinup.value()});
} else {
// We released the bumper, so let's spin down
m_loop.SetNextR(Eigen::Vector<double, 1>{0.0});

View File

@@ -48,7 +48,7 @@ void SwerveModule::SetDesiredState(
// Calculate the drive output from the drive PID controller.
const auto driveOutput = m_drivePIDController.Calculate(
m_driveEncoder.GetRate(), state.speed.to<double>());
m_driveEncoder.GetRate(), state.speed.value());
const auto driveFeedforward = m_driveFeedforward.Calculate(state.speed);

View File

@@ -51,7 +51,7 @@ void SwerveModule::SetDesiredState(
// Calculate the drive output from the drive PID controller.
const auto driveOutput = m_drivePIDController.Calculate(
m_driveEncoder.GetRate(), state.speed.to<double>());
m_driveEncoder.GetRate(), state.speed.value());
// Calculate the turning motor output from the turning PID controller.
auto turnOutput = m_turningPIDController.Calculate(

View File

@@ -20,8 +20,8 @@ SwerveModule::SwerveModule(const int driveMotorChannel,
// Set the distance per pulse for the drive encoder. We can simply use the
// distance traveled for one rotation of the wheel divided by the encoder
// resolution.
m_driveEncoder.SetDistancePerPulse(
2 * wpi::numbers::pi * kWheelRadius.to<double>() / kEncoderResolution);
m_driveEncoder.SetDistancePerPulse(2 * wpi::numbers::pi *
kWheelRadius.value() / kEncoderResolution);
// Set the distance (in this case, angle) per pulse for the turning encoder.
// This is the the angle through an entire rotation (2 * wpi::numbers::pi)
@@ -48,7 +48,7 @@ void SwerveModule::SetDesiredState(
// Calculate the drive output from the drive PID controller.
const auto driveOutput = m_drivePIDController.Calculate(
m_driveEncoder.GetRate(), state.speed.to<double>());
m_driveEncoder.GetRate(), state.speed.value());
const auto driveFeedforward = m_driveFeedforward.Calculate(state.speed);

View File

@@ -170,9 +170,9 @@ TEST_F(DIOLoopTest, SynchronousInterruptWorks) {
frc::Timer timer;
timer.Start();
interrupt.WaitForInterrupt(kSynchronousInterruptTime + 1_s);
auto time = timer.Get().to<double>();
auto time = timer.Get().value();
if (thr.joinable())
thr.join();
EXPECT_NEAR(kSynchronousInterruptTime.to<double>(), time,
kSynchronousInterruptTimeTolerance.to<double>());
EXPECT_NEAR(kSynchronousInterruptTime.value(), time,
kSynchronousInterruptTimeTolerance.value());
}

View File

@@ -7,14 +7,14 @@
namespace frc {
Eigen::Vector<double, 3> PoseTo3dVector(const Pose2d& pose) {
return Eigen::Vector<double, 3>{pose.Translation().X().to<double>(),
pose.Translation().Y().to<double>(),
pose.Rotation().Radians().to<double>()};
return Eigen::Vector<double, 3>{pose.Translation().X().value(),
pose.Translation().Y().value(),
pose.Rotation().Radians().value()};
}
Eigen::Vector<double, 4> PoseTo4dVector(const Pose2d& pose) {
return Eigen::Vector<double, 4>{pose.Translation().X().to<double>(),
pose.Translation().Y().to<double>(),
return Eigen::Vector<double, 4>{pose.Translation().X().value(),
pose.Translation().Y().value(),
pose.Rotation().Cos(), pose.Rotation().Sin()};
}
@@ -31,8 +31,8 @@ bool IsStabilizable<2, 1>(const Eigen::Matrix<double, 2, 2>& A,
}
Eigen::Vector<double, 3> PoseToVector(const Pose2d& pose) {
return Eigen::Vector<double, 3>{pose.X().to<double>(), pose.Y().to<double>(),
pose.Rotation().Radians().to<double>()};
return Eigen::Vector<double, 3>{pose.X().value(), pose.Y().value(),
pose.Rotation().Radians().value()};
}
} // namespace frc

View File

@@ -56,10 +56,10 @@ ChassisSpeeds HolonomicDriveController::Calculate(
}
// Calculate feedback velocities (based on position error).
auto xFeedback = units::meters_per_second_t(m_xController.Calculate(
currentPose.X().to<double>(), poseRef.X().to<double>()));
auto yFeedback = units::meters_per_second_t(m_yController.Calculate(
currentPose.Y().to<double>(), poseRef.Y().to<double>()));
auto xFeedback = units::meters_per_second_t(
m_xController.Calculate(currentPose.X().value(), poseRef.X().value()));
auto yFeedback = units::meters_per_second_t(
m_yController.Calculate(currentPose.Y().value(), poseRef.Y().value()));
// Return next output.
return ChassisSpeeds::FromFieldRelativeSpeeds(

View File

@@ -21,7 +21,7 @@ PIDController::PIDController(double Kp, double Ki, double Kd,
if (period <= 0_s) {
wpi::math::MathSharedStore::ReportError(
"Controller period must be a non-zero positive number, got {}!",
period.to<double>());
period.value());
m_period = 20_ms;
wpi::math::MathSharedStore::ReportWarning(
"{}", "Controller period defaulted to 20ms.");
@@ -86,7 +86,7 @@ bool PIDController::AtSetpoint() const {
positionError = m_setpoint - m_measurement;
}
double velocityError = (positionError - m_prevError) / m_period.to<double>();
double velocityError = (positionError - m_prevError) / m_period.value();
return std::abs(positionError) < m_positionTolerance &&
std::abs(velocityError) < m_velocityTolerance;
@@ -139,11 +139,11 @@ double PIDController::Calculate(double measurement) {
m_positionError = m_setpoint - measurement;
}
m_velocityError = (m_positionError - m_prevError) / m_period.to<double>();
m_velocityError = (m_positionError - m_prevError) / m_period.value();
if (m_Ki != 0) {
m_totalError =
std::clamp(m_totalError + m_positionError * m_period.to<double>(),
std::clamp(m_totalError + m_positionError * m_period.value(),
m_minimumIntegral / m_Ki, m_maximumIntegral / m_Ki);
}

View File

@@ -51,11 +51,11 @@ ChassisSpeeds RamseteController::Calculate(
m_poseError = poseRef.RelativeTo(currentPose);
// Aliases for equation readability
double eX = m_poseError.X().to<double>();
double eY = m_poseError.Y().to<double>();
double eTheta = m_poseError.Rotation().Radians().to<double>();
double vRef = linearVelocityRef.to<double>();
double omegaRef = angularVelocityRef.to<double>();
double eX = m_poseError.X().value();
double eY = m_poseError.Y().value();
double eTheta = m_poseError.Rotation().Radians().value();
double vRef = linearVelocityRef.value();
double omegaRef = angularVelocityRef.value();
double k =
2.0 * m_zeta * std::sqrt(std::pow(omegaRef, 2) + m_b * std::pow(vRef, 2));

View File

@@ -96,14 +96,12 @@ Pose2d DifferentialDrivePoseEstimator::UpdateWithTime(
auto omega = (gyroAngle - m_previousAngle).Radians() / dt;
auto u = Eigen::Vector<double, 3>{
(wheelSpeeds.left + wheelSpeeds.right).to<double>() / 2.0, 0.0,
omega.to<double>()};
(wheelSpeeds.left + wheelSpeeds.right).value() / 2.0, 0.0, omega.value()};
m_previousAngle = angle;
auto localY = Eigen::Vector<double, 3>{leftDistance.to<double>(),
rightDistance.to<double>(),
angle.Radians().to<double>()};
auto localY = Eigen::Vector<double, 3>{
leftDistance.value(), rightDistance.value(), angle.Radians().value()};
m_latencyCompensator.AddObserverState(m_observer, u, localY, currentTime);
m_observer.Predict(u, dt);
@@ -140,8 +138,8 @@ wpi::array<double, Dim> DifferentialDrivePoseEstimator::StdDevMatrixToArray(
Eigen::Vector<double, 5> DifferentialDrivePoseEstimator::FillStateVector(
const Pose2d& pose, units::meter_t leftDistance,
units::meter_t rightDistance) {
return Eigen::Vector<double, 5>{
pose.Translation().X().to<double>(), pose.Translation().Y().to<double>(),
pose.Rotation().Radians().to<double>(), leftDistance.to<double>(),
rightDistance.to<double>()};
return Eigen::Vector<double, 5>{pose.Translation().X().value(),
pose.Translation().Y().value(),
pose.Rotation().Radians().value(),
leftDistance.value(), rightDistance.value()};
}

View File

@@ -100,11 +100,11 @@ Pose2d frc::MecanumDrivePoseEstimator::UpdateWithTime(
Translation2d(chassisSpeeds.vx * 1_s, chassisSpeeds.vy * 1_s)
.RotateBy(angle);
Eigen::Vector<double, 3> u{fieldRelativeVelocities.X().to<double>(),
fieldRelativeVelocities.Y().to<double>(),
omega.to<double>()};
Eigen::Vector<double, 3> u{fieldRelativeVelocities.X().value(),
fieldRelativeVelocities.Y().value(),
omega.value()};
Eigen::Vector<double, 1> localY{angle.Radians().template to<double>()};
Eigen::Vector<double, 1> localY{angle.Radians().value()};
m_previousAngle = angle;
m_latencyCompensator.AddObserverState(m_observer, u, localY, currentTime);

View File

@@ -46,7 +46,7 @@ Pose2d Pose2d::RelativeTo(const Pose2d& other) const {
Pose2d Pose2d::Exp(const Twist2d& twist) const {
const auto dx = twist.dx;
const auto dy = twist.dy;
const auto dtheta = twist.dtheta.to<double>();
const auto dtheta = twist.dtheta.value();
const auto sinTheta = std::sin(dtheta);
const auto cosTheta = std::cos(dtheta);
@@ -68,7 +68,7 @@ Pose2d Pose2d::Exp(const Twist2d& twist) const {
Twist2d Pose2d::Log(const Pose2d& end) const {
const auto transform = end.RelativeTo(*this);
const auto dtheta = transform.Rotation().Radians().to<double>();
const auto dtheta = transform.Rotation().Radians().value();
const auto halfDtheta = dtheta / 2.0;
const auto cosMinusOne = transform.Rotation().Cos() - 1;

View File

@@ -64,7 +64,7 @@ Rotation2d Rotation2d::RotateBy(const Rotation2d& other) const {
}
void frc::to_json(wpi::json& json, const Rotation2d& rotation) {
json = wpi::json{{"radians", rotation.Radians().to<double>()}};
json = wpi::json{{"radians", rotation.Radians().value()}};
}
void frc::from_json(const wpi::json& json, Rotation2d& rotation) {

View File

@@ -59,8 +59,8 @@ bool Translation2d::operator!=(const Translation2d& other) const {
}
void frc::to_json(wpi::json& json, const Translation2d& translation) {
json = wpi::json{{"x", translation.X().to<double>()},
{"y", translation.Y().to<double>()}};
json =
wpi::json{{"x", translation.X().value()}, {"y", translation.Y().value()}};
}
void frc::from_json(const wpi::json& json, Translation2d& translation) {

View File

@@ -50,13 +50,13 @@ std::vector<double> GetElementsFromTrajectory(
elements.reserve(trajectory.States().size() * 7);
for (auto&& state : trajectory.States()) {
elements.push_back(state.t.to<double>());
elements.push_back(state.velocity.to<double>());
elements.push_back(state.acceleration.to<double>());
elements.push_back(state.pose.X().to<double>());
elements.push_back(state.pose.Y().to<double>());
elements.push_back(state.pose.Rotation().Radians().to<double>());
elements.push_back(state.curvature.to<double>());
elements.push_back(state.t.value());
elements.push_back(state.velocity.value());
elements.push_back(state.acceleration.value());
elements.push_back(state.pose.X().value());
elements.push_back(state.pose.Y().value());
elements.push_back(state.pose.Rotation().Radians().value());
elements.push_back(state.curvature.value());
}
return elements;

View File

@@ -21,9 +21,9 @@ MecanumDriveWheelSpeeds MecanumDriveKinematics::ToWheelSpeeds(
m_previousCoR = centerOfRotation;
}
Eigen::Vector3d chassisSpeedsVector{chassisSpeeds.vx.to<double>(),
chassisSpeeds.vy.to<double>(),
chassisSpeeds.omega.to<double>()};
Eigen::Vector3d chassisSpeedsVector{chassisSpeeds.vx.value(),
chassisSpeeds.vy.value(),
chassisSpeeds.omega.value()};
Eigen::Vector<double, 4> wheelsVector =
m_inverseKinematics * chassisSpeedsVector;
@@ -39,8 +39,8 @@ MecanumDriveWheelSpeeds MecanumDriveKinematics::ToWheelSpeeds(
ChassisSpeeds MecanumDriveKinematics::ToChassisSpeeds(
const MecanumDriveWheelSpeeds& wheelSpeeds) const {
Eigen::Vector<double, 4> wheelSpeedsVector{
wheelSpeeds.frontLeft.to<double>(), wheelSpeeds.frontRight.to<double>(),
wheelSpeeds.rearLeft.to<double>(), wheelSpeeds.rearRight.to<double>()};
wheelSpeeds.frontLeft.value(), wheelSpeeds.frontRight.value(),
wheelSpeeds.rearLeft.value(), wheelSpeeds.rearRight.value()};
Eigen::Vector3d chassisSpeedsVector =
m_forwardKinematics.solve(wheelSpeedsVector);
@@ -54,9 +54,9 @@ void MecanumDriveKinematics::SetInverseKinematics(Translation2d fl,
Translation2d fr,
Translation2d rl,
Translation2d rr) const {
m_inverseKinematics = Eigen::Matrix<double, 4, 3>{
{1, -1, (-(fl.X() + fl.Y())).template to<double>()},
{1, 1, (fr.X() - fr.Y()).template to<double>()},
{1, 1, (rl.X() - rl.Y()).template to<double>()},
{1, -1, (-(rr.X() + rr.Y())).template to<double>()}};
m_inverseKinematics =
Eigen::Matrix<double, 4, 3>{{1, -1, (-(fl.X() + fl.Y())).value()},
{1, 1, (fr.X() - fr.Y()).value()},
{1, 1, (rl.X() - rl.Y()).value()},
{1, -1, (-(rr.X() + rr.Y())).value()}};
}

View File

@@ -52,29 +52,27 @@ std::vector<CubicHermiteSpline> SplineHelper::CubicSplinesFromControlVectors(
c.emplace_back(0);
// populate rhs vectors
dx.emplace_back(
3 * (waypoints[2].X().to<double>() - waypoints[0].X().to<double>()) -
xInitial[1]);
dy.emplace_back(
3 * (waypoints[2].Y().to<double>() - waypoints[0].Y().to<double>()) -
yInitial[1]);
dx.emplace_back(3 * (waypoints[2].X().value() - waypoints[0].X().value()) -
xInitial[1]);
dy.emplace_back(3 * (waypoints[2].Y().value() - waypoints[0].Y().value()) -
yInitial[1]);
if (waypoints.size() > 4) {
for (size_t i = 1; i <= waypoints.size() - 4; ++i) {
// dx and dy represent the derivatives of the internal waypoints. The
// derivative of the second internal waypoint should involve the third
// and first internal waypoint, which have indices of 1 and 3 in the
// waypoints list (which contains ALL waypoints).
dx.emplace_back(3 * (waypoints[i + 2].X().to<double>() -
waypoints[i].X().to<double>()));
dy.emplace_back(3 * (waypoints[i + 2].Y().to<double>() -
waypoints[i].Y().to<double>()));
dx.emplace_back(
3 * (waypoints[i + 2].X().value() - waypoints[i].X().value()));
dy.emplace_back(
3 * (waypoints[i + 2].Y().value() - waypoints[i].Y().value()));
}
}
dx.emplace_back(3 * (waypoints[waypoints.size() - 1].X().to<double>() -
waypoints[waypoints.size() - 3].X().to<double>()) -
dx.emplace_back(3 * (waypoints[waypoints.size() - 1].X().value() -
waypoints[waypoints.size() - 3].X().value()) -
xFinal[1]);
dy.emplace_back(3 * (waypoints[waypoints.size() - 1].Y().to<double>() -
waypoints[waypoints.size() - 3].Y().to<double>()) -
dy.emplace_back(3 * (waypoints[waypoints.size() - 1].Y().value() -
waypoints[waypoints.size() - 3].Y().value()) -
yFinal[1]);
// Compute solution to tridiagonal system
@@ -89,10 +87,10 @@ std::vector<CubicHermiteSpline> SplineHelper::CubicSplinesFromControlVectors(
for (size_t i = 0; i < fx.size() - 1; ++i) {
// Create the spline.
const CubicHermiteSpline spline{
{waypoints[i].X().to<double>(), fx[i]},
{waypoints[i + 1].X().to<double>(), fx[i + 1]},
{waypoints[i].Y().to<double>(), fy[i]},
{waypoints[i + 1].Y().to<double>(), fy[i + 1]}};
{waypoints[i].X().value(), fx[i]},
{waypoints[i + 1].X().value(), fx[i + 1]},
{waypoints[i].Y().value(), fy[i]},
{waypoints[i + 1].Y().value(), fy[i + 1]}};
splines.push_back(spline);
}
@@ -102,10 +100,8 @@ std::vector<CubicHermiteSpline> SplineHelper::CubicSplinesFromControlVectors(
const double yDeriv =
(3 * (yFinal[0] - yInitial[0]) - yFinal[1] - yInitial[1]) / 4.0;
wpi::array<double, 2> midXControlVector{waypoints[0].X().to<double>(),
xDeriv};
wpi::array<double, 2> midYControlVector{waypoints[0].Y().to<double>(),
yDeriv};
wpi::array<double, 2> midXControlVector{waypoints[0].X().value(), xDeriv};
wpi::array<double, 2> midYControlVector{waypoints[0].Y().value(), yDeriv};
splines.emplace_back(xInitial, midXControlVector, yInitial,
midYControlVector);
@@ -140,16 +136,14 @@ SplineHelper::CubicControlVectorsFromWaypoints(
const Pose2d& end) {
double scalar;
if (interiorWaypoints.empty()) {
scalar = 1.2 * start.Translation().Distance(end.Translation()).to<double>();
scalar = 1.2 * start.Translation().Distance(end.Translation()).value();
} else {
scalar =
1.2 *
start.Translation().Distance(interiorWaypoints.front()).to<double>();
1.2 * start.Translation().Distance(interiorWaypoints.front()).value();
}
const auto initialCV = CubicControlVector(scalar, start);
if (!interiorWaypoints.empty()) {
scalar =
1.2 * end.Translation().Distance(interiorWaypoints.back()).to<double>();
scalar = 1.2 * end.Translation().Distance(interiorWaypoints.back()).value();
}
const auto finalCV = CubicControlVector(scalar, end);
return {initialCV, finalCV};
@@ -165,7 +159,7 @@ std::vector<QuinticHermiteSpline> SplineHelper::QuinticSplinesFromWaypoints(
// This just makes the splines look better.
const auto scalar =
1.2 * p0.Translation().Distance(p1.Translation()).to<double>();
1.2 * p0.Translation().Distance(p1.Translation()).value();
auto controlVectorA = QuinticControlVector(scalar, p0);
auto controlVectorB = QuinticControlVector(scalar, p1);

View File

@@ -146,11 +146,11 @@ Trajectory Trajectory::operator+(const Trajectory& other) const {
}
void frc::to_json(wpi::json& json, const Trajectory::State& state) {
json = wpi::json{{"time", state.t.to<double>()},
{"velocity", state.velocity.to<double>()},
{"acceleration", state.acceleration.to<double>()},
json = wpi::json{{"time", state.t.value()},
{"velocity", state.velocity.value()},
{"acceleration", state.acceleration.value()},
{"pose", state.pose},
{"curvature", state.curvature.to<double>()}};
{"curvature", state.curvature.value()}};
}
void frc::from_json(const wpi::json& json, Trajectory::State& state) {

View File

@@ -85,7 +85,7 @@ Trajectory TrajectoryParameterizer::TimeParameterizeTrajectory(
// Now enforce all acceleration limits.
EnforceAccelerationLimits(reversed, constraints, &constrainedState);
if (ds.to<double>() < kEpsilon) {
if (ds.value() < kEpsilon) {
break;
}
@@ -141,7 +141,7 @@ Trajectory TrajectoryParameterizer::TimeParameterizeTrajectory(
// Check all acceleration constraints with the new max velocity.
EnforceAccelerationLimits(reversed, constraints, &constrainedState);
if (ds.to<double>() > -kEpsilon) {
if (ds.value() > -kEpsilon) {
break;
}

View File

@@ -166,7 +166,7 @@ class ControlAffinePlantInversionFeedforward {
Eigen::Vector<double, Inputs> Calculate(
const Eigen::Vector<double, States>& r,
const Eigen::Vector<double, States>& nextR) {
Eigen::Vector<double, States> rDot = (nextR - r) / m_dt.to<double>();
Eigen::Vector<double, States> rDot = (nextR - r) / m_dt.value();
m_uff = m_B.householderQr().solve(
rDot - m_f(r, Eigen::Vector<double, Inputs>::Zero()));

View File

@@ -193,8 +193,8 @@ class ProfiledPIDController
* @param maximumInput The maximum value expected from the input.
*/
void EnableContinuousInput(Distance_t minimumInput, Distance_t maximumInput) {
m_controller.EnableContinuousInput(minimumInput.template to<double>(),
maximumInput.template to<double>());
m_controller.EnableContinuousInput(minimumInput.value(),
maximumInput.value());
m_minimumInput = minimumInput;
m_maximumInput = maximumInput;
}
@@ -227,8 +227,8 @@ class ProfiledPIDController
void SetTolerance(
Distance_t positionTolerance,
Velocity_t velocityTolerance = std::numeric_limits<double>::infinity()) {
m_controller.SetTolerance(positionTolerance.template to<double>(),
velocityTolerance.template to<double>());
m_controller.SetTolerance(positionTolerance.value(),
velocityTolerance.value());
}
/**
@@ -273,8 +273,8 @@ class ProfiledPIDController
frc::TrapezoidProfile<Distance> profile{m_constraints, m_goal, m_setpoint};
m_setpoint = profile.Calculate(GetPeriod());
return m_controller.Calculate(measurement.template to<double>(),
m_setpoint.position.template to<double>());
return m_controller.Calculate(measurement.value(),
m_setpoint.position.value());
}
/**
@@ -351,7 +351,7 @@ class ProfiledPIDController
builder.AddDoubleProperty(
"d", [this] { return GetD(); }, [this](double value) { SetD(value); });
builder.AddDoubleProperty(
"goal", [this] { return GetGoal().position.template to<double>(); },
"goal", [this] { return GetGoal().position.value(); },
[this](double value) { SetGoal(Distance_t{value}); });
}

View File

@@ -70,10 +70,10 @@ class SimpleMotorFeedforward {
auto plant = LinearSystemId::IdentifyVelocitySystem<Distance>(kV, kA);
LinearPlantInversionFeedforward<1, 1> feedforward{plant, dt};
Eigen::Vector<double, 1> r{currentVelocity.template to<double>()};
Eigen::Vector<double, 1> nextR{nextVelocity.template to<double>()};
Eigen::Vector<double, 1> r{currentVelocity.value()};
Eigen::Vector<double, 1> nextR{nextVelocity.value()};
return kS * wpi::sgn(currentVelocity.template to<double>()) +
return kS * wpi::sgn(currentVelocity.value()) +
units::volt_t{feedforward.Calculate(r, nextR)(0)};
}

View File

@@ -25,7 +25,7 @@ Eigen::Vector<double, States> AngleResidual(
const Eigen::Vector<double, States>& b, int angleStateIdx) {
Eigen::Vector<double, States> ret = a - b;
ret[angleStateIdx] =
AngleModulus(units::radian_t{ret[angleStateIdx]}).to<double>();
AngleModulus(units::radian_t{ret[angleStateIdx]}).value();
return ret;
}

View File

@@ -269,11 +269,10 @@ class SwerveDrivePoseEstimator {
Translation2d(chassisSpeeds.vx * 1_s, chassisSpeeds.vy * 1_s)
.RotateBy(angle);
Eigen::Vector<double, 3> u{fieldRelativeSpeeds.X().template to<double>(),
fieldRelativeSpeeds.Y().template to<double>(),
omega.template to<double>()};
Eigen::Vector<double, 3> u{fieldRelativeSpeeds.X().value(),
fieldRelativeSpeeds.Y().value(), omega.value()};
Eigen::Vector<double, 1> localY{angle.Radians().template to<double>()};
Eigen::Vector<double, 1> localY{angle.Radians().value()};
m_previousAngle = angle;
m_latencyCompensator.AddObserverState(m_observer, u, localY, currentTime);

View File

@@ -125,7 +125,7 @@ class LinearFilter {
*/
static LinearFilter<T> SinglePoleIIR(double timeConstant,
units::second_t period) {
double gain = std::exp(-period.to<double>() / timeConstant);
double gain = std::exp(-period.value() / timeConstant);
return LinearFilter({1.0 - gain}, {-gain});
}
@@ -144,7 +144,7 @@ class LinearFilter {
* user.
*/
static LinearFilter<T> HighPass(double timeConstant, units::second_t period) {
double gain = std::exp(-period.to<double>() / timeConstant);
double gain = std::exp(-period.value() / timeConstant);
return LinearFilter({gain, -gain}, {-gain});
}
@@ -225,7 +225,7 @@ class LinearFilter {
}
Eigen::Vector<double, Samples> a =
S.householderQr().solve(d) / std::pow(period.to<double>(), Derivative);
S.householderQr().solve(d) / std::pow(period.value(), Derivative);
// Reverse gains list
std::vector<double> gains;

View File

@@ -65,8 +65,8 @@ class SwerveDriveKinematics {
for (size_t i = 0; i < NumModules; i++) {
// clang-format off
m_inverseKinematics.template block<2, 3>(i * 2, 0) <<
1, 0, (-m_modules[i].Y()).template to<double>(),
0, 1, (+m_modules[i].X()).template to<double>();
1, 0, (-m_modules[i].Y()).value(),
0, 1, (+m_modules[i].X()).value();
// clang-format on
}
@@ -82,8 +82,8 @@ class SwerveDriveKinematics {
for (size_t i = 0; i < NumModules; i++) {
// clang-format off
m_inverseKinematics.template block<2, 3>(i * 2, 0) <<
1, 0, (-m_modules[i].Y()).template to<double>(),
0, 1, (+m_modules[i].X()).template to<double>();
1, 0, (-m_modules[i].Y()).value(),
0, 1, (+m_modules[i].X()).value();
// clang-format on
}

View File

@@ -26,16 +26,16 @@ SwerveDriveKinematics<NumModules>::ToSwerveModuleStates(
// clang-format off
m_inverseKinematics.template block<2, 3>(i * 2, 0) =
Eigen::Matrix<double, 2, 3>{
{1, 0, (-m_modules[i].Y() + centerOfRotation.Y()).template to<double>()},
{0, 1, (+m_modules[i].X() - centerOfRotation.X()).template to<double>()}};
{1, 0, (-m_modules[i].Y() + centerOfRotation.Y()).value()},
{0, 1, (+m_modules[i].X() - centerOfRotation.X()).value()}};
// clang-format on
}
m_previousCoR = centerOfRotation;
}
Eigen::Vector3d chassisSpeedsVector{chassisSpeeds.vx.to<double>(),
chassisSpeeds.vy.to<double>(),
chassisSpeeds.omega.to<double>()};
Eigen::Vector3d chassisSpeedsVector{chassisSpeeds.vx.value(),
chassisSpeeds.vy.value(),
chassisSpeeds.omega.value()};
Eigen::Matrix<double, NumModules * 2, 1> moduleStatesMatrix =
m_inverseKinematics * chassisSpeedsVector;
@@ -46,7 +46,7 @@ SwerveDriveKinematics<NumModules>::ToSwerveModuleStates(
units::meters_per_second_t y{moduleStatesMatrix(i * 2 + 1, 0)};
auto speed = units::math::hypot(x, y);
Rotation2d rotation{x.to<double>(), y.to<double>()};
Rotation2d rotation{x.value(), y.value()};
moduleStates[i] = {speed, rotation};
}
@@ -74,10 +74,9 @@ ChassisSpeeds SwerveDriveKinematics<NumModules>::ToChassisSpeeds(
for (size_t i = 0; i < NumModules; ++i) {
SwerveModuleState module = moduleStates[i];
moduleStatesMatrix(i * 2, 0) =
module.speed.to<double>() * module.angle.Cos();
moduleStatesMatrix(i * 2, 0) = module.speed.value() * module.angle.Cos();
moduleStatesMatrix(i * 2 + 1, 0) =
module.speed.to<double>() * module.angle.Sin();
module.speed.value() * module.angle.Sin();
}
Eigen::Vector3d chassisSpeedsVector =

View File

@@ -109,8 +109,7 @@ class Spline {
* @return The vector.
*/
static Eigen::Vector2d ToVector(const Translation2d& translation) {
return Eigen::Vector2d{translation.X().to<double>(),
translation.Y().to<double>()};
return Eigen::Vector2d{translation.X().value(), translation.Y().value()};
}
/**

View File

@@ -80,14 +80,14 @@ class WPILIB_DLLEXPORT SplineHelper {
private:
static Spline<3>::ControlVector CubicControlVector(double scalar,
const Pose2d& point) {
return {{point.X().to<double>(), scalar * point.Rotation().Cos()},
{point.Y().to<double>(), scalar * point.Rotation().Sin()}};
return {{point.X().value(), scalar * point.Rotation().Cos()},
{point.Y().value(), scalar * point.Rotation().Sin()}};
}
static Spline<5>::ControlVector QuinticControlVector(double scalar,
const Pose2d& point) {
return {{point.X().to<double>(), scalar * point.Rotation().Cos(), 0.0},
{point.Y().to<double>(), scalar * point.Rotation().Sin(), 0.0}};
return {{point.X().value(), scalar * point.Rotation().Cos(), 0.0},
{point.Y().value(), scalar * point.Rotation().Sin(), 0.0}};
}
/**

View File

@@ -21,7 +21,7 @@ template <int States>
void DiscretizeA(const Eigen::Matrix<double, States, States>& contA,
units::second_t dt,
Eigen::Matrix<double, States, States>* discA) {
*discA = (contA * dt.to<double>()).exp();
*discA = (contA * dt.value()).exp();
}
/**
@@ -42,8 +42,8 @@ void DiscretizeAB(const Eigen::Matrix<double, States, States>& contA,
// Matrices are blocked here to minimize matrix exponentiation calculations
Eigen::Matrix<double, States + Inputs, States + Inputs> Mcont;
Mcont.setZero();
Mcont.template block<States, States>(0, 0) = contA * dt.to<double>();
Mcont.template block<States, Inputs>(0, States) = contB * dt.to<double>();
Mcont.template block<States, States>(0, 0) = contA * dt.value();
Mcont.template block<States, Inputs>(0, States) = contB * dt.value();
// Discretize A and B with the given timestep
Eigen::Matrix<double, States + Inputs, States + Inputs> Mdisc = Mcont.exp();
@@ -76,8 +76,7 @@ void DiscretizeAQ(const Eigen::Matrix<double, States, States>& contA,
M.template block<States, States>(States, 0).setZero();
M.template block<States, States>(States, States) = contA.transpose();
Eigen::Matrix<double, 2 * States, 2 * States> phi =
(M * dt.to<double>()).exp();
Eigen::Matrix<double, 2 * States, 2 * States> phi = (M * dt.value()).exp();
// Phi12 = phi[0:States, States:2*States]
// Phi22 = phi[States:2*States, States:2*States]
@@ -122,7 +121,7 @@ void DiscretizeAQTaylor(const Eigen::Matrix<double, States, States>& contA,
Eigen::Matrix<double, States, States> Q = (contQ + contQ.transpose()) / 2.0;
Eigen::Matrix<double, States, States> lastTerm = Q;
double lastCoeff = dt.to<double>();
double lastCoeff = dt.value();
// Aᵀⁿ
Eigen::Matrix<double, States, States> Atn = contA.transpose();
@@ -132,7 +131,7 @@ void DiscretizeAQTaylor(const Eigen::Matrix<double, States, States>& contA,
// i = 6 i.e. 5th order should be enough precision
for (int i = 2; i < 6; ++i) {
lastTerm = -contA * lastTerm + Q * Atn;
lastCoeff *= dt.to<double>() / static_cast<double>(i);
lastCoeff *= dt.value() / static_cast<double>(i);
phi12 += lastTerm * lastCoeff;
@@ -156,7 +155,7 @@ void DiscretizeAQTaylor(const Eigen::Matrix<double, States, States>& contA,
template <int Outputs>
Eigen::Matrix<double, Outputs, Outputs> DiscretizeR(
const Eigen::Matrix<double, Outputs, Outputs>& R, units::second_t dt) {
return R / dt.to<double>();
return R / dt.value();
}
} // namespace frc

View File

@@ -50,8 +50,7 @@ class LinearSystemLoop {
: LinearSystemLoop(
plant, controller, observer,
[=](const Eigen::Vector<double, Inputs>& u) {
return frc::NormalizeInputVector<Inputs>(
u, maxVoltage.template to<double>());
return frc::NormalizeInputVector<Inputs>(u, maxVoltage.value());
},
dt) {}
@@ -97,7 +96,7 @@ class LinearSystemLoop {
: LinearSystemLoop(controller, feedforward, observer,
[=](const Eigen::Vector<double, Inputs>& u) {
return frc::NormalizeInputVector<Inputs>(
u, maxVoltage.template to<double>());
u, maxVoltage.value());
}) {}
/**

View File

@@ -23,7 +23,7 @@ namespace frc {
*/
template <typename F, typename T>
T RK4(F&& f, T x, units::second_t dt) {
const auto h = dt.to<double>();
const auto h = dt.value();
T k1 = f(x);
T k2 = f(x + h * 0.5 * k1);
@@ -43,7 +43,7 @@ T RK4(F&& f, T x, units::second_t dt) {
*/
template <typename F, typename T, typename U>
T RK4(F&& f, T x, U u, units::second_t dt) {
const auto h = dt.to<double>();
const auto h = dt.value();
T k1 = f(x, u);
T k2 = f(x + h * 0.5 * k1, u);
@@ -91,13 +91,13 @@ T RKF45(F&& f, T x, U u, units::second_t dt, double maxError = 1e-6) {
double truncationError;
double dtElapsed = 0.0;
double h = dt.to<double>();
double h = dt.value();
// Loop until we've gotten to our desired dt
while (dtElapsed < dt.to<double>()) {
while (dtElapsed < dt.value()) {
do {
// Only allow us to advance up to the dt remaining
h = std::min(h, dt.to<double>() - dtElapsed);
h = std::min(h, dt.value() - dtElapsed);
// Notice how the derivative in the Wikipedia notation is dy/dx.
// That means their y is our x and their x is our t
@@ -167,13 +167,13 @@ T RKDP(F&& f, T x, U u, units::second_t dt, double maxError = 1e-6) {
double truncationError;
double dtElapsed = 0.0;
double h = dt.to<double>();
double h = dt.value();
// Loop until we've gotten to our desired dt
while (dtElapsed < dt.to<double>()) {
while (dtElapsed < dt.value()) {
do {
// Only allow us to advance up to the dt remaining
h = std::min(h, dt.to<double>() - dtElapsed);
h = std::min(h, dt.value() - dtElapsed);
// clang-format off
T k1 = f(x, u);

View File

@@ -47,9 +47,9 @@ class WPILIB_DLLEXPORT LinearSystemId {
{0.0, 1.0},
{0.0, (-std::pow(G, 2) * motor.Kt /
(motor.R * units::math::pow<2>(r) * m * motor.Kv))
.to<double>()}};
Eigen::Matrix<double, 2, 1> B{
0.0, (G * motor.Kt / (motor.R * r * m)).to<double>()};
.value()}};
Eigen::Matrix<double, 2, 1> B{0.0,
(G * motor.Kt / (motor.R * r * m)).value()};
Eigen::Matrix<double, 1, 2> C{1.0, 0.0};
Eigen::Matrix<double, 1, 1> D{0.0};
@@ -71,10 +71,8 @@ class WPILIB_DLLEXPORT LinearSystemId {
DCMotor motor, units::kilogram_square_meter_t J, double G) {
Eigen::Matrix<double, 2, 2> A{
{0.0, 1.0},
{0.0,
(-std::pow(G, 2) * motor.Kt / (motor.Kv * motor.R * J)).to<double>()}};
Eigen::Matrix<double, 2, 1> B{0.0,
(G * motor.Kt / (motor.R * J)).to<double>()};
{0.0, (-std::pow(G, 2) * motor.Kt / (motor.Kv * motor.R * J)).value()}};
Eigen::Matrix<double, 2, 1> B{0.0, (G * motor.Kt / (motor.R * J)).value()};
Eigen::Matrix<double, 1, 2> C{1.0, 0.0};
Eigen::Matrix<double, 1, 1> D{0.0};
@@ -107,9 +105,8 @@ class WPILIB_DLLEXPORT LinearSystemId {
static LinearSystem<1, 1, 1> IdentifyVelocitySystem(
decltype(1_V / Velocity_t<Distance>(1)) kV,
decltype(1_V / Acceleration_t<Distance>(1)) kA) {
Eigen::Matrix<double, 1, 1> A{-kV.template to<double>() /
kA.template to<double>()};
Eigen::Matrix<double, 1, 1> B{1.0 / kA.template to<double>()};
Eigen::Matrix<double, 1, 1> A{-kV.value() / kA.value()};
Eigen::Matrix<double, 1, 1> B{1.0 / kA.value()};
Eigen::Matrix<double, 1, 1> C{1.0};
Eigen::Matrix<double, 1, 1> D{0.0};
@@ -142,10 +139,8 @@ class WPILIB_DLLEXPORT LinearSystemId {
static LinearSystem<2, 1, 1> IdentifyPositionSystem(
decltype(1_V / Velocity_t<Distance>(1)) kV,
decltype(1_V / Acceleration_t<Distance>(1)) kA) {
Eigen::Matrix<double, 2, 2> A{
{0.0, 1.0},
{0.0, -kV.template to<double>() / kA.template to<double>()}};
Eigen::Matrix<double, 2, 1> B{0.0, 1.0 / kA.template to<double>()};
Eigen::Matrix<double, 2, 2> A{{0.0, 1.0}, {0.0, -kV.value() / kA.value()}};
Eigen::Matrix<double, 2, 1> B{0.0, 1.0 / kA.value()};
Eigen::Matrix<double, 1, 2> C{1.0, 0.0};
Eigen::Matrix<double, 1, 1> D{0.0};
@@ -170,12 +165,12 @@ class WPILIB_DLLEXPORT LinearSystemId {
static LinearSystem<2, 2, 2> IdentifyDrivetrainSystem(
decltype(1_V / 1_mps) kVlinear, decltype(1_V / 1_mps_sq) kAlinear,
decltype(1_V / 1_mps) kVangular, decltype(1_V / 1_mps_sq) kAangular) {
double A1 = -(kVlinear.to<double>() / kAlinear.to<double>() +
kVangular.to<double>() / kAangular.to<double>());
double A2 = -(kVlinear.to<double>() / kAlinear.to<double>() -
kVangular.to<double>() / kAangular.to<double>());
double B1 = 1.0 / kAlinear.to<double>() + 1.0 / kAangular.to<double>();
double B2 = 1.0 / kAlinear.to<double>() - 1.0 / kAangular.to<double>();
double A1 = -(kVlinear.value() / kAlinear.value() +
kVangular.value() / kAangular.value());
double A2 = -(kVlinear.value() / kAlinear.value() -
kVangular.value() / kAangular.value());
double B1 = 1.0 / kAlinear.value() + 1.0 / kAangular.value();
double B2 = 1.0 / kAlinear.value() - 1.0 / kAangular.value();
Eigen::Matrix<double, 2, 2> A =
0.5 * Eigen::Matrix<double, 2, 2>{{A1, A2}, {A2, A1}};
@@ -239,8 +234,8 @@ class WPILIB_DLLEXPORT LinearSystemId {
units::kilogram_square_meter_t J,
double G) {
Eigen::Matrix<double, 1, 1> A{
(-std::pow(G, 2) * motor.Kt / (motor.Kv * motor.R * J)).to<double>()};
Eigen::Matrix<double, 1, 1> B{(G * motor.Kt / (motor.R * J)).to<double>()};
(-std::pow(G, 2) * motor.Kt / (motor.Kv * motor.R * J)).value()};
Eigen::Matrix<double, 1, 1> B{(G * motor.Kt / (motor.R * J)).value()};
Eigen::Matrix<double, 1, 1> C{1.0};
Eigen::Matrix<double, 1, 1> D{0.0};
@@ -269,15 +264,15 @@ class WPILIB_DLLEXPORT LinearSystemId {
auto C2 = G * motor.Kt / (motor.R * r);
Eigen::Matrix<double, 2, 2> A{
{((1 / m + units::math::pow<2>(rb) / J) * C1).to<double>(),
((1 / m - units::math::pow<2>(rb) / J) * C1).to<double>()},
{((1 / m - units::math::pow<2>(rb) / J) * C1).to<double>(),
((1 / m + units::math::pow<2>(rb) / J) * C1).to<double>()}};
{((1 / m + units::math::pow<2>(rb) / J) * C1).value(),
((1 / m - units::math::pow<2>(rb) / J) * C1).value()},
{((1 / m - units::math::pow<2>(rb) / J) * C1).value(),
((1 / m + units::math::pow<2>(rb) / J) * C1).value()}};
Eigen::Matrix<double, 2, 2> B{
{((1 / m + units::math::pow<2>(rb) / J) * C2).to<double>(),
((1 / m - units::math::pow<2>(rb) / J) * C2).to<double>()},
{((1 / m - units::math::pow<2>(rb) / J) * C2).to<double>(),
((1 / m + units::math::pow<2>(rb) / J) * C2).to<double>()}};
{((1 / m + units::math::pow<2>(rb) / J) * C2).value(),
((1 / m - units::math::pow<2>(rb) / J) * C2).value()},
{((1 / m - units::math::pow<2>(rb) / J) * C2).value(),
((1 / m + units::math::pow<2>(rb) / J) * C2).value()}};
Eigen::Matrix<double, 2, 2> C{{1.0, 0.0}, {0.0, 1.0}};
Eigen::Matrix<double, 2, 2> D{{0.0, 0.0}, {0.0, 0.0}};

Some files were not shown because too many files have changed in this diff Show More