[wpiutil] Change Struct to allow non-constexpr implementation (#5992)

This required changing the constant values (e.g. kSize) into functions
(e.g. GetSize()).

Fixed implementations of ForEachNested to be inline (as these are actually
templates).

Also added a ntcore Struct test.
This commit is contained in:
Peter Johnson
2023-12-02 23:36:44 -08:00
committed by GitHub
parent ca272de400
commit a583ca01e1
62 changed files with 812 additions and 450 deletions

View File

@@ -7,26 +7,19 @@
namespace {
constexpr size_t kTranslationOff = 0;
constexpr size_t kRotationOff =
kTranslationOff + wpi::Struct<frc::Translation2d>::kSize;
kTranslationOff + wpi::GetStructSize<frc::Translation2d>();
} // namespace
using StructType = wpi::Struct<frc::Pose2d>;
frc::Pose2d StructType::Unpack(std::span<const uint8_t, kSize> data) {
frc::Pose2d StructType::Unpack(std::span<const uint8_t> data) {
return frc::Pose2d{
wpi::UnpackStruct<frc::Translation2d, kTranslationOff>(data),
wpi::UnpackStruct<frc::Rotation2d, kRotationOff>(data),
};
}
void StructType::Pack(std::span<uint8_t, kSize> data,
const frc::Pose2d& value) {
void StructType::Pack(std::span<uint8_t> data, const frc::Pose2d& value) {
wpi::PackStruct<kTranslationOff>(data, value.Translation());
wpi::PackStruct<kRotationOff>(data, value.Rotation());
}
void StructType::ForEachNested(
std::invocable<std::string_view, std::string_view> auto fn) {
wpi::ForEachStructSchema<frc::Translation2d>(fn);
wpi::ForEachStructSchema<frc::Rotation2d>(fn);
}

View File

@@ -7,26 +7,19 @@
namespace {
constexpr size_t kTranslationOff = 0;
constexpr size_t kRotationOff =
kTranslationOff + wpi::Struct<frc::Translation3d>::kSize;
kTranslationOff + wpi::GetStructSize<frc::Translation3d>();
} // namespace
using StructType = wpi::Struct<frc::Pose3d>;
frc::Pose3d StructType::Unpack(std::span<const uint8_t, kSize> data) {
frc::Pose3d StructType::Unpack(std::span<const uint8_t> data) {
return frc::Pose3d{
wpi::UnpackStruct<frc::Translation3d, kTranslationOff>(data),
wpi::UnpackStruct<frc::Rotation3d, kRotationOff>(data),
};
}
void StructType::Pack(std::span<uint8_t, kSize> data,
const frc::Pose3d& value) {
void StructType::Pack(std::span<uint8_t> data, const frc::Pose3d& value) {
wpi::PackStruct<kTranslationOff>(data, value.Translation());
wpi::PackStruct<kRotationOff>(data, value.Rotation());
}
void StructType::ForEachNested(
std::invocable<std::string_view, std::string_view> auto fn) {
wpi::ForEachStructSchema<frc::Translation3d>(fn);
wpi::ForEachStructSchema<frc::Rotation3d>(fn);
}

View File

@@ -13,7 +13,7 @@ constexpr size_t kZOff = kYOff + 8;
using StructType = wpi::Struct<frc::Quaternion>;
frc::Quaternion StructType::Unpack(std::span<const uint8_t, kSize> data) {
frc::Quaternion StructType::Unpack(std::span<const uint8_t> data) {
return frc::Quaternion{
wpi::UnpackStruct<double, kWOff>(data),
wpi::UnpackStruct<double, kXOff>(data),
@@ -22,8 +22,7 @@ frc::Quaternion StructType::Unpack(std::span<const uint8_t, kSize> data) {
};
}
void StructType::Pack(std::span<uint8_t, kSize> data,
const frc::Quaternion& value) {
void StructType::Pack(std::span<uint8_t> data, const frc::Quaternion& value) {
wpi::PackStruct<kWOff>(data, value.W());
wpi::PackStruct<kXOff>(data, value.X());
wpi::PackStruct<kYOff>(data, value.Y());

View File

@@ -10,13 +10,12 @@ constexpr size_t kValueOff = 0;
using StructType = wpi::Struct<frc::Rotation2d>;
frc::Rotation2d StructType::Unpack(std::span<const uint8_t, kSize> data) {
frc::Rotation2d StructType::Unpack(std::span<const uint8_t> data) {
return frc::Rotation2d{
units::radian_t{wpi::UnpackStruct<double, kValueOff>(data)},
};
}
void StructType::Pack(std::span<uint8_t, kSize> data,
const frc::Rotation2d& value) {
void StructType::Pack(std::span<uint8_t> data, const frc::Rotation2d& value) {
wpi::PackStruct<kValueOff>(data, value.Radians().value());
}

View File

@@ -10,18 +10,12 @@ constexpr size_t kQOff = 0;
using StructType = wpi::Struct<frc::Rotation3d>;
frc::Rotation3d StructType::Unpack(std::span<const uint8_t, kSize> data) {
frc::Rotation3d StructType::Unpack(std::span<const uint8_t> data) {
return frc::Rotation3d{
wpi::UnpackStruct<frc::Quaternion, kQOff>(data),
};
}
void StructType::Pack(std::span<uint8_t, kSize> data,
const frc::Rotation3d& value) {
void StructType::Pack(std::span<uint8_t> data, const frc::Rotation3d& value) {
wpi::PackStruct<kQOff>(data, value.GetQuaternion());
}
void StructType::ForEachNested(
std::invocable<std::string_view, std::string_view> auto fn) {
wpi::ForEachStructSchema<frc::Quaternion>(fn);
}

View File

@@ -7,26 +7,19 @@
namespace {
constexpr size_t kTranslationOff = 0;
constexpr size_t kRotationOff =
kTranslationOff + wpi::Struct<frc::Translation2d>::kSize;
kTranslationOff + wpi::GetStructSize<frc::Translation2d>();
} // namespace
using StructType = wpi::Struct<frc::Transform2d>;
frc::Transform2d StructType::Unpack(std::span<const uint8_t, kSize> data) {
frc::Transform2d StructType::Unpack(std::span<const uint8_t> data) {
return frc::Transform2d{
wpi::UnpackStruct<frc::Translation2d, kTranslationOff>(data),
wpi::UnpackStruct<frc::Rotation2d, kRotationOff>(data),
};
}
void StructType::Pack(std::span<uint8_t, kSize> data,
const frc::Transform2d& value) {
void StructType::Pack(std::span<uint8_t> data, const frc::Transform2d& value) {
wpi::PackStruct<kTranslationOff>(data, value.Translation());
wpi::PackStruct<kRotationOff>(data, value.Rotation());
}
void StructType::ForEachNested(
std::invocable<std::string_view, std::string_view> auto fn) {
wpi::ForEachStructSchema<frc::Translation2d>(fn);
wpi::ForEachStructSchema<frc::Rotation2d>(fn);
}

View File

@@ -7,26 +7,19 @@
namespace {
constexpr size_t kTranslationOff = 0;
constexpr size_t kRotationOff =
kTranslationOff + wpi::Struct<frc::Translation3d>::kSize;
kTranslationOff + wpi::GetStructSize<frc::Translation3d>();
} // namespace
using StructType = wpi::Struct<frc::Transform3d>;
frc::Transform3d StructType::Unpack(std::span<const uint8_t, kSize> data) {
frc::Transform3d StructType::Unpack(std::span<const uint8_t> data) {
return frc::Transform3d{
wpi::UnpackStruct<frc::Translation3d, kTranslationOff>(data),
wpi::UnpackStruct<frc::Rotation3d, kRotationOff>(data),
};
}
void StructType::Pack(std::span<uint8_t, kSize> data,
const frc::Transform3d& value) {
void StructType::Pack(std::span<uint8_t> data, const frc::Transform3d& value) {
wpi::PackStruct<kTranslationOff>(data, value.Translation());
wpi::PackStruct<kRotationOff>(data, value.Rotation());
}
void StructType::ForEachNested(
std::invocable<std::string_view, std::string_view> auto fn) {
wpi::ForEachStructSchema<frc::Translation3d>(fn);
wpi::ForEachStructSchema<frc::Rotation3d>(fn);
}

View File

@@ -11,14 +11,14 @@ constexpr size_t kYOff = kXOff + 8;
using StructType = wpi::Struct<frc::Translation2d>;
frc::Translation2d StructType::Unpack(std::span<const uint8_t, kSize> data) {
frc::Translation2d StructType::Unpack(std::span<const uint8_t> data) {
return frc::Translation2d{
units::meter_t{wpi::UnpackStruct<double, kXOff>(data)},
units::meter_t{wpi::UnpackStruct<double, kYOff>(data)},
};
}
void StructType::Pack(std::span<uint8_t, kSize> data,
void StructType::Pack(std::span<uint8_t> data,
const frc::Translation2d& value) {
wpi::PackStruct<kXOff>(data, value.X().value());
wpi::PackStruct<kYOff>(data, value.Y().value());

View File

@@ -12,7 +12,7 @@ constexpr size_t kZOff = kYOff + 8;
using StructType = wpi::Struct<frc::Translation3d>;
frc::Translation3d StructType::Unpack(std::span<const uint8_t, kSize> data) {
frc::Translation3d StructType::Unpack(std::span<const uint8_t> data) {
return frc::Translation3d{
units::meter_t{wpi::UnpackStruct<double, kXOff>(data)},
units::meter_t{wpi::UnpackStruct<double, kYOff>(data)},
@@ -20,7 +20,7 @@ frc::Translation3d 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::Translation3d& value) {
wpi::PackStruct<kXOff>(data, value.X().value());
wpi::PackStruct<kYOff>(data, value.Y().value());

View File

@@ -12,7 +12,7 @@ constexpr size_t kDthetaOff = kDyOff + 8;
using StructType = wpi::Struct<frc::Twist2d>;
frc::Twist2d StructType::Unpack(std::span<const uint8_t, kSize> data) {
frc::Twist2d StructType::Unpack(std::span<const uint8_t> data) {
return frc::Twist2d{
units::meter_t{wpi::UnpackStruct<double, kDxOff>(data)},
units::meter_t{wpi::UnpackStruct<double, kDyOff>(data)},
@@ -20,8 +20,7 @@ frc::Twist2d StructType::Unpack(std::span<const uint8_t, kSize> data) {
};
}
void StructType::Pack(std::span<uint8_t, kSize> data,
const frc::Twist2d& value) {
void StructType::Pack(std::span<uint8_t> data, const frc::Twist2d& value) {
wpi::PackStruct<kDxOff>(data, value.dx.value());
wpi::PackStruct<kDyOff>(data, value.dy.value());
wpi::PackStruct<kDthetaOff>(data, value.dtheta.value());

View File

@@ -15,7 +15,7 @@ constexpr size_t kRzOff = kRyOff + 8;
using StructType = wpi::Struct<frc::Twist3d>;
frc::Twist3d StructType::Unpack(std::span<const uint8_t, kSize> data) {
frc::Twist3d StructType::Unpack(std::span<const uint8_t> data) {
return frc::Twist3d{
units::meter_t{wpi::UnpackStruct<double, kDxOff>(data)},
units::meter_t{wpi::UnpackStruct<double, kDyOff>(data)},
@@ -26,8 +26,7 @@ frc::Twist3d StructType::Unpack(std::span<const uint8_t, kSize> data) {
};
}
void StructType::Pack(std::span<uint8_t, kSize> data,
const frc::Twist3d& value) {
void StructType::Pack(std::span<uint8_t> data, const frc::Twist3d& value) {
wpi::PackStruct<kDxOff>(data, value.dx.value());
wpi::PackStruct<kDyOff>(data, value.dy.value());
wpi::PackStruct<kDzOff>(data, value.dz.value());