[wpimath] Struct cleanup (#6011)

This commit is contained in:
Joseph Eng
2023-12-04 22:40:18 -08:00
committed by GitHub
parent 90757b9e90
commit 14c3ade155
32 changed files with 95 additions and 49 deletions

View File

@@ -13,7 +13,7 @@ constexpr size_t kKaOff = kKvOff + 8;
using StructType = wpi::Struct<frc::ArmFeedforward>;
frc::ArmFeedforward StructType::Unpack(std::span<const uint8_t, kSize> data) {
frc::ArmFeedforward StructType::Unpack(std::span<const uint8_t> data) {
return frc::ArmFeedforward{
units::volt_t{wpi::UnpackStruct<double, kKsOff>(data)},
units::volt_t{wpi::UnpackStruct<double, kKgOff>(data)},
@@ -24,7 +24,7 @@ frc::ArmFeedforward StructType::Unpack(std::span<const uint8_t, kSize> data) {
};
}
void StructType::Pack(std::span<uint8_t, kSize> data,
void StructType::Pack(std::span<uint8_t> data,
const frc::ArmFeedforward& value) {
wpi::PackStruct<kKsOff>(data, value.kS());
wpi::PackStruct<kKgOff>(data, value.kG());

View File

@@ -12,14 +12,14 @@ constexpr size_t kRightOff = kLeftOff + 8;
using StructType = wpi::Struct<frc::DifferentialDriveWheelVoltages>;
frc::DifferentialDriveWheelVoltages StructType::Unpack(
std::span<const uint8_t, kSize> data) {
std::span<const uint8_t> data) {
return frc::DifferentialDriveWheelVoltages{
units::volt_t{wpi::UnpackStruct<double, kLeftOff>(data)},
units::volt_t{wpi::UnpackStruct<double, kRightOff>(data)},
};
}
void StructType::Pack(std::span<uint8_t, kSize> data,
void StructType::Pack(std::span<uint8_t> data,
const frc::DifferentialDriveWheelVoltages& value) {
wpi::PackStruct<kLeftOff>(data, value.left.value());
wpi::PackStruct<kRightOff>(data, value.right.value());

View File

@@ -13,8 +13,7 @@ constexpr size_t kKaOff = kKvOff + 8;
using StructType = wpi::Struct<frc::ElevatorFeedforward>;
frc::ElevatorFeedforward StructType::Unpack(
std::span<const uint8_t, kSize> data) {
frc::ElevatorFeedforward StructType::Unpack(std::span<const uint8_t> data) {
return frc::ElevatorFeedforward{
units::volt_t{wpi::UnpackStruct<double, kKsOff>(data)},
units::volt_t{wpi::UnpackStruct<double, kKgOff>(data)},
@@ -25,7 +24,7 @@ frc::ElevatorFeedforward StructType::Unpack(
};
}
void StructType::Pack(std::span<uint8_t, kSize> data,
void StructType::Pack(std::span<uint8_t> data,
const frc::ElevatorFeedforward& value) {
wpi::PackStruct<kKsOff>(data, value.kS());
wpi::PackStruct<kKgOff>(data, value.kG());

View File

@@ -14,7 +14,7 @@ constexpr size_t kFreeSpeedOff = kFreeCurrentOff + 8;
using StructType = wpi::Struct<frc::DCMotor>;
frc::DCMotor StructType::Unpack(std::span<const uint8_t, kSize> data) {
frc::DCMotor StructType::Unpack(std::span<const uint8_t> data) {
return frc::DCMotor{
units::volt_t{wpi::UnpackStruct<double, kNominalVoltageOff>(data)},
units::newton_meter_t{wpi::UnpackStruct<double, kStallTorqueOff>(data)},
@@ -25,8 +25,7 @@ frc::DCMotor StructType::Unpack(std::span<const uint8_t, kSize> data) {
};
}
void StructType::Pack(std::span<uint8_t, kSize> data,
const frc::DCMotor& value) {
void StructType::Pack(std::span<uint8_t> data, const frc::DCMotor& value) {
wpi::PackStruct<kNominalVoltageOff>(data, value.nominalVoltage.value());
wpi::PackStruct<kStallTorqueOff>(data, value.stallTorque.value());
wpi::PackStruct<kStallCurrentOff>(data, value.stallCurrent.value());