mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-19 00:41:43 +00:00
[wpiutil] Struct: Change from GetTypeString() to GetTypeName() (#6872)
This makes it easier to define schemas when the type name is non-trivial (e.g., templated structs). This is breaking for a) custom struct implementations and b) anything calling `wpi::Struct<T>::GetTypeString(info...)` in C++ directly. In both cases, it's a simple translation: For A, rename `GetTypeString()` to `GetTypeName()` and remove the struct: at the beginning, and for B, use `wpi::GetStructTypeString<T>(info...)` instead.
This commit is contained in:
@@ -46,7 +46,7 @@ struct Info1 {
|
||||
|
||||
template <>
|
||||
struct wpi::Struct<Inner> {
|
||||
static constexpr std::string_view GetTypeString() { return "struct:Inner"; }
|
||||
static constexpr std::string_view GetTypeName() { return "Inner"; }
|
||||
static constexpr size_t GetSize() { return 8; }
|
||||
static constexpr std::string_view GetSchema() { return "int32 a; int32 b"; }
|
||||
|
||||
@@ -62,7 +62,7 @@ struct wpi::Struct<Inner> {
|
||||
|
||||
template <>
|
||||
struct wpi::Struct<Outer> {
|
||||
static constexpr std::string_view GetTypeString() { return "struct:Outer"; }
|
||||
static constexpr std::string_view GetTypeName() { return "Outer"; }
|
||||
static constexpr size_t GetSize() { return wpi::GetStructSize<Inner>() + 4; }
|
||||
static constexpr std::string_view GetSchema() {
|
||||
return "Inner inner; int32 c";
|
||||
@@ -86,7 +86,7 @@ struct wpi::Struct<Outer> {
|
||||
|
||||
template <>
|
||||
struct wpi::Struct<Inner2> {
|
||||
static std::string_view GetTypeString() { return "struct:Inner2"; }
|
||||
static std::string_view GetTypeName() { return "Inner2"; }
|
||||
static size_t GetSize() { return 8; }
|
||||
static std::string_view GetSchema() { return "int32 a; int32 b"; }
|
||||
|
||||
@@ -102,7 +102,7 @@ struct wpi::Struct<Inner2> {
|
||||
|
||||
template <>
|
||||
struct wpi::Struct<Outer2> {
|
||||
static std::string_view GetTypeString() { return "struct:Outer2"; }
|
||||
static std::string_view GetTypeName() { return "Outer2"; }
|
||||
static size_t GetSize() { return wpi::GetStructSize<Inner>() + 4; }
|
||||
static std::string_view GetSchema() { return "Inner2 inner; int32 c"; }
|
||||
|
||||
@@ -124,7 +124,7 @@ struct wpi::Struct<Outer2> {
|
||||
|
||||
template <>
|
||||
struct wpi::Struct<ThingA> {
|
||||
static constexpr std::string_view GetTypeString() { return "struct:ThingA"; }
|
||||
static constexpr std::string_view GetTypeName() { return "ThingA"; }
|
||||
static constexpr size_t GetSize() { return 1; }
|
||||
static constexpr std::string_view GetSchema() { return "uint8 value"; }
|
||||
static ThingA Unpack(std::span<const uint8_t> data) {
|
||||
@@ -137,8 +137,8 @@ struct wpi::Struct<ThingA> {
|
||||
|
||||
template <>
|
||||
struct wpi::Struct<ThingB, Info1> {
|
||||
static constexpr std::string_view GetTypeString(const Info1&) {
|
||||
return "struct:ThingB";
|
||||
static constexpr std::string_view GetTypeName(const Info1&) {
|
||||
return "ThingB";
|
||||
}
|
||||
static constexpr size_t GetSize(const Info1&) { return 1; }
|
||||
static constexpr std::string_view GetSchema(const Info1&) {
|
||||
|
||||
@@ -15,8 +15,8 @@ public class ArmFeedforwardStruct implements Struct<ArmFeedforward> {
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getTypeString() {
|
||||
return "struct:ArmFeedforward";
|
||||
public String getTypeName() {
|
||||
return "ArmFeedforward";
|
||||
}
|
||||
|
||||
@Override
|
||||
|
||||
@@ -16,8 +16,8 @@ public class DifferentialDriveWheelVoltagesStruct
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getTypeString() {
|
||||
return "struct:DifferentialDriveWheelVoltages";
|
||||
public String getTypeName() {
|
||||
return "DifferentialDriveWheelVoltages";
|
||||
}
|
||||
|
||||
@Override
|
||||
|
||||
@@ -15,8 +15,8 @@ public class ElevatorFeedforwardStruct implements Struct<ElevatorFeedforward> {
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getTypeString() {
|
||||
return "struct:ElevatorFeedforward";
|
||||
public String getTypeName() {
|
||||
return "ElevatorFeedforward";
|
||||
}
|
||||
|
||||
@Override
|
||||
|
||||
@@ -16,8 +16,8 @@ public class Ellipse2dStruct implements Struct<Ellipse2d> {
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getTypeString() {
|
||||
return "struct:Ellipse2d";
|
||||
public String getTypeName() {
|
||||
return "Ellipse2d";
|
||||
}
|
||||
|
||||
@Override
|
||||
|
||||
@@ -17,8 +17,8 @@ public class Pose2dStruct implements Struct<Pose2d> {
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getTypeString() {
|
||||
return "struct:Pose2d";
|
||||
public String getTypeName() {
|
||||
return "Pose2d";
|
||||
}
|
||||
|
||||
@Override
|
||||
|
||||
@@ -17,8 +17,8 @@ public class Pose3dStruct implements Struct<Pose3d> {
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getTypeString() {
|
||||
return "struct:Pose3d";
|
||||
public String getTypeName() {
|
||||
return "Pose3d";
|
||||
}
|
||||
|
||||
@Override
|
||||
|
||||
@@ -15,8 +15,8 @@ public class QuaternionStruct implements Struct<Quaternion> {
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getTypeString() {
|
||||
return "struct:Quaternion";
|
||||
public String getTypeName() {
|
||||
return "Quaternion";
|
||||
}
|
||||
|
||||
@Override
|
||||
|
||||
@@ -16,8 +16,8 @@ public class Rectangle2dStruct implements Struct<Rectangle2d> {
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getTypeString() {
|
||||
return "struct:Rectangle2d";
|
||||
public String getTypeName() {
|
||||
return "Rectangle2d";
|
||||
}
|
||||
|
||||
@Override
|
||||
|
||||
@@ -15,8 +15,8 @@ public class Rotation2dStruct implements Struct<Rotation2d> {
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getTypeString() {
|
||||
return "struct:Rotation2d";
|
||||
public String getTypeName() {
|
||||
return "Rotation2d";
|
||||
}
|
||||
|
||||
@Override
|
||||
|
||||
@@ -16,8 +16,8 @@ public class Rotation3dStruct implements Struct<Rotation3d> {
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getTypeString() {
|
||||
return "struct:Rotation3d";
|
||||
public String getTypeName() {
|
||||
return "Rotation3d";
|
||||
}
|
||||
|
||||
@Override
|
||||
|
||||
@@ -17,8 +17,8 @@ public class Transform2dStruct implements Struct<Transform2d> {
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getTypeString() {
|
||||
return "struct:Transform2d";
|
||||
public String getTypeName() {
|
||||
return "Transform2d";
|
||||
}
|
||||
|
||||
@Override
|
||||
|
||||
@@ -17,8 +17,8 @@ public class Transform3dStruct implements Struct<Transform3d> {
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getTypeString() {
|
||||
return "struct:Transform3d";
|
||||
public String getTypeName() {
|
||||
return "Transform3d";
|
||||
}
|
||||
|
||||
@Override
|
||||
|
||||
@@ -15,8 +15,8 @@ public class Translation2dStruct implements Struct<Translation2d> {
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getTypeString() {
|
||||
return "struct:Translation2d";
|
||||
public String getTypeName() {
|
||||
return "Translation2d";
|
||||
}
|
||||
|
||||
@Override
|
||||
|
||||
@@ -15,8 +15,8 @@ public class Translation3dStruct implements Struct<Translation3d> {
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getTypeString() {
|
||||
return "struct:Translation3d";
|
||||
public String getTypeName() {
|
||||
return "Translation3d";
|
||||
}
|
||||
|
||||
@Override
|
||||
|
||||
@@ -15,8 +15,8 @@ public class Twist2dStruct implements Struct<Twist2d> {
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getTypeString() {
|
||||
return "struct:Twist2d";
|
||||
public String getTypeName() {
|
||||
return "Twist2d";
|
||||
}
|
||||
|
||||
@Override
|
||||
|
||||
@@ -15,8 +15,8 @@ public class Twist3dStruct implements Struct<Twist3d> {
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getTypeString() {
|
||||
return "struct:Twist3d";
|
||||
public String getTypeName() {
|
||||
return "Twist3d";
|
||||
}
|
||||
|
||||
@Override
|
||||
|
||||
@@ -15,8 +15,8 @@ public class ChassisSpeedsStruct implements Struct<ChassisSpeeds> {
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getTypeString() {
|
||||
return "struct:ChassisSpeeds";
|
||||
public String getTypeName() {
|
||||
return "ChassisSpeeds";
|
||||
}
|
||||
|
||||
@Override
|
||||
|
||||
@@ -15,8 +15,8 @@ public class DifferentialDriveKinematicsStruct implements Struct<DifferentialDri
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getTypeString() {
|
||||
return "struct:DifferentialDriveKinematics";
|
||||
public String getTypeName() {
|
||||
return "DifferentialDriveKinematics";
|
||||
}
|
||||
|
||||
@Override
|
||||
|
||||
@@ -16,8 +16,8 @@ public class DifferentialDriveWheelPositionsStruct
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getTypeString() {
|
||||
return "struct:DifferentialDriveWheelPositions";
|
||||
public String getTypeName() {
|
||||
return "DifferentialDriveWheelPositions";
|
||||
}
|
||||
|
||||
@Override
|
||||
|
||||
@@ -15,8 +15,8 @@ public class DifferentialDriveWheelSpeedsStruct implements Struct<DifferentialDr
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getTypeString() {
|
||||
return "struct:DifferentialDriveWheelSpeeds";
|
||||
public String getTypeName() {
|
||||
return "DifferentialDriveWheelSpeeds";
|
||||
}
|
||||
|
||||
@Override
|
||||
|
||||
@@ -16,8 +16,8 @@ public class MecanumDriveKinematicsStruct implements Struct<MecanumDriveKinemati
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getTypeString() {
|
||||
return "struct:MecanumDriveKinematics";
|
||||
public String getTypeName() {
|
||||
return "MecanumDriveKinematics";
|
||||
}
|
||||
|
||||
@Override
|
||||
|
||||
@@ -15,8 +15,8 @@ public class MecanumDriveWheelPositionsStruct implements Struct<MecanumDriveWhee
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getTypeString() {
|
||||
return "struct:MecanumDriveWheelPositions";
|
||||
public String getTypeName() {
|
||||
return "MecanumDriveWheelPositions";
|
||||
}
|
||||
|
||||
@Override
|
||||
|
||||
@@ -15,8 +15,8 @@ public class MecanumDriveWheelSpeedsStruct implements Struct<MecanumDriveWheelSp
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getTypeString() {
|
||||
return "struct:MecanumDriveWheelSpeeds";
|
||||
public String getTypeName() {
|
||||
return "MecanumDriveWheelSpeeds";
|
||||
}
|
||||
|
||||
@Override
|
||||
|
||||
@@ -16,8 +16,8 @@ public class SwerveModulePositionStruct implements Struct<SwerveModulePosition>
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getTypeString() {
|
||||
return "struct:SwerveModulePosition";
|
||||
public String getTypeName() {
|
||||
return "SwerveModulePosition";
|
||||
}
|
||||
|
||||
@Override
|
||||
|
||||
@@ -16,8 +16,8 @@ public class SwerveModuleStateStruct implements Struct<SwerveModuleState> {
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getTypeString() {
|
||||
return "struct:SwerveModuleState";
|
||||
public String getTypeName() {
|
||||
return "SwerveModuleState";
|
||||
}
|
||||
|
||||
@Override
|
||||
|
||||
@@ -15,8 +15,8 @@ public class DCMotorStruct implements Struct<DCMotor> {
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getTypeString() {
|
||||
return "struct:DCMotor";
|
||||
public String getTypeName() {
|
||||
return "DCMotor";
|
||||
}
|
||||
|
||||
@Override
|
||||
|
||||
@@ -11,9 +11,7 @@
|
||||
|
||||
template <>
|
||||
struct WPILIB_DLLEXPORT wpi::Struct<frc::ArmFeedforward> {
|
||||
static constexpr std::string_view GetTypeString() {
|
||||
return "struct:ArmFeedforward";
|
||||
}
|
||||
static constexpr std::string_view GetTypeName() { return "ArmFeedforward"; }
|
||||
static constexpr size_t GetSize() { return 32; }
|
||||
static constexpr std::string_view GetSchema() {
|
||||
return "double ks;double kg;double kv;double ka";
|
||||
|
||||
@@ -11,8 +11,8 @@
|
||||
|
||||
template <>
|
||||
struct WPILIB_DLLEXPORT wpi::Struct<frc::DifferentialDriveWheelVoltages> {
|
||||
static constexpr std::string_view GetTypeString() {
|
||||
return "struct:DifferentialDriveWheelVoltages";
|
||||
static constexpr std::string_view GetTypeName() {
|
||||
return "DifferentialDriveWheelVoltages";
|
||||
}
|
||||
static constexpr size_t GetSize() { return 16; }
|
||||
static constexpr std::string_view GetSchema() {
|
||||
|
||||
@@ -11,8 +11,8 @@
|
||||
|
||||
template <>
|
||||
struct WPILIB_DLLEXPORT wpi::Struct<frc::ElevatorFeedforward> {
|
||||
static constexpr std::string_view GetTypeString() {
|
||||
return "struct:ElevatorFeedforward";
|
||||
static constexpr std::string_view GetTypeName() {
|
||||
return "ElevatorFeedforward";
|
||||
}
|
||||
static constexpr size_t GetSize() { return 32; }
|
||||
static constexpr std::string_view GetSchema() {
|
||||
|
||||
@@ -11,9 +11,7 @@
|
||||
|
||||
template <>
|
||||
struct WPILIB_DLLEXPORT wpi::Struct<frc::Ellipse2d> {
|
||||
static constexpr std::string_view GetTypeString() {
|
||||
return "struct:Ellipse2d";
|
||||
}
|
||||
static constexpr std::string_view GetTypeName() { return "Ellipse2d"; }
|
||||
static constexpr size_t GetSize() {
|
||||
return wpi::GetStructSize<frc::Pose2d>() + 16;
|
||||
}
|
||||
|
||||
@@ -11,7 +11,7 @@
|
||||
|
||||
template <>
|
||||
struct WPILIB_DLLEXPORT wpi::Struct<frc::Pose2d> {
|
||||
static constexpr std::string_view GetTypeString() { return "struct:Pose2d"; }
|
||||
static constexpr std::string_view GetTypeName() { return "Pose2d"; }
|
||||
static constexpr size_t GetSize() {
|
||||
return wpi::GetStructSize<frc::Translation2d>() +
|
||||
wpi::GetStructSize<frc::Rotation2d>();
|
||||
|
||||
@@ -11,7 +11,7 @@
|
||||
|
||||
template <>
|
||||
struct WPILIB_DLLEXPORT wpi::Struct<frc::Pose3d> {
|
||||
static constexpr std::string_view GetTypeString() { return "struct:Pose3d"; }
|
||||
static constexpr std::string_view GetTypeName() { return "Pose3d"; }
|
||||
static constexpr size_t GetSize() {
|
||||
return wpi::GetStructSize<frc::Translation3d>() +
|
||||
wpi::GetStructSize<frc::Rotation3d>();
|
||||
|
||||
@@ -11,9 +11,7 @@
|
||||
|
||||
template <>
|
||||
struct WPILIB_DLLEXPORT wpi::Struct<frc::Quaternion> {
|
||||
static constexpr std::string_view GetTypeString() {
|
||||
return "struct:Quaternion";
|
||||
}
|
||||
static constexpr std::string_view GetTypeName() { return "Quaternion"; }
|
||||
static constexpr size_t GetSize() { return 32; }
|
||||
static constexpr std::string_view GetSchema() {
|
||||
return "double w;double x;double y;double z";
|
||||
|
||||
@@ -11,9 +11,7 @@
|
||||
|
||||
template <>
|
||||
struct WPILIB_DLLEXPORT wpi::Struct<frc::Rectangle2d> {
|
||||
static constexpr std::string_view GetTypeString() {
|
||||
return "struct:Rectangle2d";
|
||||
}
|
||||
static constexpr std::string_view GetTypeName() { return "Rectangle2d"; }
|
||||
static constexpr size_t GetSize() {
|
||||
return wpi::GetStructSize<frc::Pose2d>() + 16;
|
||||
}
|
||||
|
||||
@@ -11,9 +11,7 @@
|
||||
|
||||
template <>
|
||||
struct WPILIB_DLLEXPORT wpi::Struct<frc::Rotation2d> {
|
||||
static constexpr std::string_view GetTypeString() {
|
||||
return "struct:Rotation2d";
|
||||
}
|
||||
static constexpr std::string_view GetTypeName() { return "Rotation2d"; }
|
||||
static constexpr size_t GetSize() { return 8; }
|
||||
static constexpr std::string_view GetSchema() { return "double value"; }
|
||||
|
||||
|
||||
@@ -11,9 +11,7 @@
|
||||
|
||||
template <>
|
||||
struct WPILIB_DLLEXPORT wpi::Struct<frc::Rotation3d> {
|
||||
static constexpr std::string_view GetTypeString() {
|
||||
return "struct:Rotation3d";
|
||||
}
|
||||
static constexpr std::string_view GetTypeName() { return "Rotation3d"; }
|
||||
static constexpr size_t GetSize() {
|
||||
return wpi::GetStructSize<frc::Quaternion>();
|
||||
}
|
||||
|
||||
@@ -11,9 +11,7 @@
|
||||
|
||||
template <>
|
||||
struct WPILIB_DLLEXPORT wpi::Struct<frc::Transform2d> {
|
||||
static constexpr std::string_view GetTypeString() {
|
||||
return "struct:Transform2d";
|
||||
}
|
||||
static constexpr std::string_view GetTypeName() { return "Transform2d"; }
|
||||
static constexpr size_t GetSize() {
|
||||
return wpi::GetStructSize<frc::Translation2d>() +
|
||||
wpi::GetStructSize<frc::Rotation2d>();
|
||||
|
||||
@@ -11,9 +11,7 @@
|
||||
|
||||
template <>
|
||||
struct WPILIB_DLLEXPORT wpi::Struct<frc::Transform3d> {
|
||||
static constexpr std::string_view GetTypeString() {
|
||||
return "struct:Transform3d";
|
||||
}
|
||||
static constexpr std::string_view GetTypeName() { return "Transform3d"; }
|
||||
static constexpr size_t GetSize() {
|
||||
return wpi::GetStructSize<frc::Translation3d>() +
|
||||
wpi::GetStructSize<frc::Rotation3d>();
|
||||
|
||||
@@ -11,9 +11,7 @@
|
||||
|
||||
template <>
|
||||
struct WPILIB_DLLEXPORT wpi::Struct<frc::Translation2d> {
|
||||
static constexpr std::string_view GetTypeString() {
|
||||
return "struct:Translation2d";
|
||||
}
|
||||
static constexpr std::string_view GetTypeName() { return "Translation2d"; }
|
||||
static constexpr size_t GetSize() { return 16; }
|
||||
static constexpr std::string_view GetSchema() { return "double x;double y"; }
|
||||
|
||||
|
||||
@@ -11,9 +11,7 @@
|
||||
|
||||
template <>
|
||||
struct WPILIB_DLLEXPORT wpi::Struct<frc::Translation3d> {
|
||||
static constexpr std::string_view GetTypeString() {
|
||||
return "struct:Translation3d";
|
||||
}
|
||||
static constexpr std::string_view GetTypeName() { return "Translation3d"; }
|
||||
static constexpr size_t GetSize() { return 24; }
|
||||
static constexpr std::string_view GetSchema() {
|
||||
return "double x;double y;double z";
|
||||
|
||||
@@ -11,7 +11,7 @@
|
||||
|
||||
template <>
|
||||
struct WPILIB_DLLEXPORT wpi::Struct<frc::Twist2d> {
|
||||
static constexpr std::string_view GetTypeString() { return "struct:Twist2d"; }
|
||||
static constexpr std::string_view GetTypeName() { return "Twist2d"; }
|
||||
static constexpr size_t GetSize() { return 24; }
|
||||
static constexpr std::string_view GetSchema() {
|
||||
return "double dx;double dy;double dtheta";
|
||||
|
||||
@@ -11,7 +11,7 @@
|
||||
|
||||
template <>
|
||||
struct WPILIB_DLLEXPORT wpi::Struct<frc::Twist3d> {
|
||||
static constexpr std::string_view GetTypeString() { return "struct:Twist3d"; }
|
||||
static constexpr std::string_view GetTypeName() { return "Twist3d"; }
|
||||
static constexpr size_t GetSize() { return 48; }
|
||||
static constexpr std::string_view GetSchema() {
|
||||
return "double dx;double dy;double dz;double rx;double ry;double rz";
|
||||
|
||||
@@ -11,9 +11,7 @@
|
||||
|
||||
template <>
|
||||
struct WPILIB_DLLEXPORT wpi::Struct<frc::ChassisSpeeds> {
|
||||
static constexpr std::string_view GetTypeString() {
|
||||
return "struct:ChassisSpeeds";
|
||||
}
|
||||
static constexpr std::string_view GetTypeName() { return "ChassisSpeeds"; }
|
||||
static constexpr size_t GetSize() { return 24; }
|
||||
static constexpr std::string_view GetSchema() {
|
||||
return "double vx;double vy;double omega";
|
||||
|
||||
@@ -11,8 +11,8 @@
|
||||
|
||||
template <>
|
||||
struct WPILIB_DLLEXPORT wpi::Struct<frc::DifferentialDriveKinematics> {
|
||||
static constexpr std::string_view GetTypeString() {
|
||||
return "struct:DifferentialDriveKinematics";
|
||||
static constexpr std::string_view GetTypeName() {
|
||||
return "DifferentialDriveKinematics";
|
||||
}
|
||||
static constexpr size_t GetSize() { return 8; }
|
||||
static constexpr std::string_view GetSchema() { return "double track_width"; }
|
||||
|
||||
@@ -11,8 +11,8 @@
|
||||
|
||||
template <>
|
||||
struct WPILIB_DLLEXPORT wpi::Struct<frc::DifferentialDriveWheelPositions> {
|
||||
static constexpr std::string_view GetTypeString() {
|
||||
return "struct:DifferentialDriveWheelPositions";
|
||||
static constexpr std::string_view GetTypeName() {
|
||||
return "DifferentialDriveWheelPositions";
|
||||
}
|
||||
static constexpr size_t GetSize() { return 16; }
|
||||
static constexpr std::string_view GetSchema() {
|
||||
|
||||
@@ -11,8 +11,8 @@
|
||||
|
||||
template <>
|
||||
struct WPILIB_DLLEXPORT wpi::Struct<frc::DifferentialDriveWheelSpeeds> {
|
||||
static constexpr std::string_view GetTypeString() {
|
||||
return "struct:DifferentialDriveWheelSpeeds";
|
||||
static constexpr std::string_view GetTypeName() {
|
||||
return "DifferentialDriveWheelSpeeds";
|
||||
}
|
||||
static constexpr size_t GetSize() { return 16; }
|
||||
static constexpr std::string_view GetSchema() {
|
||||
|
||||
@@ -11,8 +11,8 @@
|
||||
|
||||
template <>
|
||||
struct WPILIB_DLLEXPORT wpi::Struct<frc::MecanumDriveKinematics> {
|
||||
static constexpr std::string_view GetTypeString() {
|
||||
return "struct:MecanumDriveKinematics";
|
||||
static constexpr std::string_view GetTypeName() {
|
||||
return "MecanumDriveKinematics";
|
||||
}
|
||||
static constexpr size_t GetSize() {
|
||||
return 4 * wpi::GetStructSize<frc::Translation2d>();
|
||||
|
||||
@@ -11,8 +11,8 @@
|
||||
|
||||
template <>
|
||||
struct WPILIB_DLLEXPORT wpi::Struct<frc::MecanumDriveWheelPositions> {
|
||||
static constexpr std::string_view GetTypeString() {
|
||||
return "struct:MecanumDriveWheelPositions";
|
||||
static constexpr std::string_view GetTypeName() {
|
||||
return "MecanumDriveWheelPositions";
|
||||
}
|
||||
static constexpr size_t GetSize() { return 32; }
|
||||
static constexpr std::string_view GetSchema() {
|
||||
|
||||
@@ -11,8 +11,8 @@
|
||||
|
||||
template <>
|
||||
struct WPILIB_DLLEXPORT wpi::Struct<frc::MecanumDriveWheelSpeeds> {
|
||||
static constexpr std::string_view GetTypeString() {
|
||||
return "struct:MecanumDriveWheelSpeeds";
|
||||
static constexpr std::string_view GetTypeName() {
|
||||
return "MecanumDriveWheelSpeeds";
|
||||
}
|
||||
static constexpr size_t GetSize() { return 32; }
|
||||
static constexpr std::string_view GetSchema() {
|
||||
|
||||
@@ -11,8 +11,8 @@
|
||||
|
||||
template <>
|
||||
struct WPILIB_DLLEXPORT wpi::Struct<frc::SwerveModulePosition> {
|
||||
static constexpr std::string_view GetTypeString() {
|
||||
return "struct:SwerveModulePosition";
|
||||
static constexpr std::string_view GetTypeName() {
|
||||
return "SwerveModulePosition";
|
||||
}
|
||||
static constexpr size_t GetSize() {
|
||||
return 8 + wpi::GetStructSize<frc::Rotation2d>();
|
||||
|
||||
@@ -11,8 +11,8 @@
|
||||
|
||||
template <>
|
||||
struct WPILIB_DLLEXPORT wpi::Struct<frc::SwerveModuleState> {
|
||||
static constexpr std::string_view GetTypeString() {
|
||||
return "struct:SwerveModuleState";
|
||||
static constexpr std::string_view GetTypeName() {
|
||||
return "SwerveModuleState";
|
||||
}
|
||||
static constexpr size_t GetSize() {
|
||||
return 8 + wpi::GetStructSize<frc::Rotation2d>();
|
||||
|
||||
@@ -11,7 +11,7 @@
|
||||
|
||||
template <>
|
||||
struct WPILIB_DLLEXPORT wpi::Struct<frc::DCMotor> {
|
||||
static constexpr std::string_view GetTypeString() { return "struct:DCMotor"; }
|
||||
static constexpr std::string_view GetTypeName() { return "DCMotor"; }
|
||||
static constexpr size_t GetSize() { return 40; }
|
||||
static constexpr std::string_view GetSchema() {
|
||||
return "double nominal_voltage;double stall_torque;double "
|
||||
|
||||
@@ -47,13 +47,23 @@ public interface Struct<T> {
|
||||
*/
|
||||
Class<T> getTypeClass();
|
||||
|
||||
/**
|
||||
* Gets the type name (e.g. for schemas of other structs). This should be globally unique among
|
||||
* structs.
|
||||
*
|
||||
* @return type name
|
||||
*/
|
||||
String getTypeName();
|
||||
|
||||
/**
|
||||
* Gets the type string (e.g. for NetworkTables). This should be globally unique and start with
|
||||
* "struct:".
|
||||
*
|
||||
* @return type string
|
||||
*/
|
||||
String getTypeString();
|
||||
default String getTypeString() {
|
||||
return "struct:" + getTypeName();
|
||||
}
|
||||
|
||||
/**
|
||||
* Gets the serialized size (in bytes). This should always be a constant.
|
||||
|
||||
@@ -1309,7 +1309,8 @@ class StructLogEntry : public DataLogEntry {
|
||||
: m_info{std::move(info)...} {
|
||||
m_log = &log;
|
||||
log.AddStructSchema<T, I...>(info..., timestamp);
|
||||
m_entry = log.Start(name, S::GetTypeString(info...), metadata, timestamp);
|
||||
m_entry =
|
||||
log.Start(name, GetStructTypeString<T>(info...), metadata, timestamp);
|
||||
}
|
||||
|
||||
StructLogEntry(StructLogEntry&& rhs)
|
||||
|
||||
@@ -49,15 +49,15 @@ struct Struct {};
|
||||
* Implementations must define a template specialization for wpi::Struct with
|
||||
* T being the type that is being serialized/deserialized, with the following
|
||||
* static members (as enforced by this concept):
|
||||
* - std::string_view GetTypeString(): function that returns the type string
|
||||
* - std::string_view GetTypeName(): function that returns the type name
|
||||
* - size_t GetSize(): function that returns the structure size in bytes
|
||||
* - std::string_view GetSchema(): function that returns the struct schema
|
||||
* - T Unpack(std::span<const uint8_t>): function for deserialization
|
||||
* - void Pack(std::span<uint8_t>, T&& value): function for
|
||||
* serialization
|
||||
*
|
||||
* If possible, the GetTypeString(), GetSize(), and GetSchema() functions should
|
||||
* be marked constexpr. GetTypeString() and GetSchema() may return types other
|
||||
* If possible, the GetTypeName(), GetSize(), and GetSchema() functions should
|
||||
* be marked constexpr. GetTypeName() and GetSchema() may return types other
|
||||
* than std::string_view, as long as the return value is convertible to
|
||||
* std::string_view.
|
||||
*
|
||||
@@ -72,7 +72,7 @@ concept StructSerializable = requires(std::span<const uint8_t> in,
|
||||
typename std::remove_cvref_t<I>...>;
|
||||
{
|
||||
Struct<typename std::remove_cvref_t<T>,
|
||||
typename std::remove_cvref_t<I>...>::GetTypeString(info...)
|
||||
typename std::remove_cvref_t<I>...>::GetTypeName(info...)
|
||||
} -> std::convertible_to<std::string_view>;
|
||||
{
|
||||
Struct<typename std::remove_cvref_t<T>,
|
||||
@@ -229,18 +229,41 @@ inline void UnpackStructInto(T* out, std::span<const uint8_t> data,
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the type name for a raw struct serializable type
|
||||
*
|
||||
* @tparam T serializable type
|
||||
* @param info optional struct type info
|
||||
* @return type name
|
||||
*/
|
||||
template <typename T, typename... I>
|
||||
requires StructSerializable<T, I...>
|
||||
constexpr auto GetStructTypeName(const I&... info) {
|
||||
using S = Struct<T, typename std::remove_cvref_t<I>...>;
|
||||
return S::GetTypeName(info...);
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the type string for a raw struct serializable type
|
||||
*
|
||||
* @tparam T serializable type
|
||||
* @param info optional struct type info
|
||||
* @return type string
|
||||
* @return type string (struct: followed by type name)
|
||||
*/
|
||||
template <typename T, typename... I>
|
||||
requires StructSerializable<T, I...>
|
||||
constexpr auto GetStructTypeString(const I&... info) {
|
||||
using S = Struct<T, typename std::remove_cvref_t<I>...>;
|
||||
return S::GetTypeString(info...);
|
||||
if constexpr (sizeof...(I) == 0 &&
|
||||
is_constexpr([&] { S::GetTypeName(info...); })) {
|
||||
constexpr auto typeName = S::GetTypeName(info...);
|
||||
using namespace literals;
|
||||
return Concat(
|
||||
"struct:"_ct_string,
|
||||
ct_string<char, std::char_traits<char>, typeName.size()>{typeName});
|
||||
} else {
|
||||
return fmt::format("struct:{}", S::GetTypeName(info...));
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -259,32 +282,43 @@ constexpr size_t GetStructSize(const I&... info) {
|
||||
|
||||
template <typename T, size_t N, typename... I>
|
||||
requires StructSerializable<T, I...>
|
||||
constexpr auto MakeStructArrayTypeString(const I&... info) {
|
||||
constexpr auto MakeStructArrayTypeName(const I&... info) {
|
||||
using S = Struct<T, typename std::remove_cvref_t<I>...>;
|
||||
if constexpr (sizeof...(I) == 0 &&
|
||||
is_constexpr([&] { S::GetTypeString(info...); })) {
|
||||
constexpr auto typeString = S::GetTypeString(info...);
|
||||
is_constexpr([&] { S::GetTypeName(info...); })) {
|
||||
constexpr auto typeName = S::GetTypeName(info...);
|
||||
using namespace literals;
|
||||
if constexpr (N == std::dynamic_extent) {
|
||||
return Concat(
|
||||
ct_string<char, std::char_traits<char>, typeString.size()>{
|
||||
typeString},
|
||||
ct_string<char, std::char_traits<char>, typeName.size()>{typeName},
|
||||
"[]"_ct_string);
|
||||
} else {
|
||||
return Concat(
|
||||
ct_string<char, std::char_traits<char>, typeString.size()>{
|
||||
typeString},
|
||||
ct_string<char, std::char_traits<char>, typeName.size()>{typeName},
|
||||
"["_ct_string, NumToCtString<N>(), "]"_ct_string);
|
||||
}
|
||||
} else {
|
||||
if constexpr (N == std::dynamic_extent) {
|
||||
return fmt::format("{}[]", S::GetTypeString(info...));
|
||||
return fmt::format("{}[]", S::GetTypeName(info...));
|
||||
} else {
|
||||
return fmt::format("{}[{}]", S::GetTypeString(info...), N);
|
||||
return fmt::format("{}[{}]", S::GetTypeName(info...), N);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
template <typename T, size_t N, typename... I>
|
||||
requires StructSerializable<T, I...>
|
||||
constexpr auto MakeStructArrayTypeString(const I&... info) {
|
||||
using S = Struct<T, typename std::remove_cvref_t<I>...>;
|
||||
if constexpr (sizeof...(I) == 0 &&
|
||||
is_constexpr([&] { S::GetTypeName(info...); })) {
|
||||
using namespace literals;
|
||||
return Concat("struct:"_ct_string, MakeStructArrayTypeName<T, N>(info...));
|
||||
} else {
|
||||
return fmt::format("struct:{}", MakeStructArrayTypeName<T, N>(info...));
|
||||
}
|
||||
}
|
||||
|
||||
template <typename T, size_t N, typename... I>
|
||||
requires StructSerializable<T, I...>
|
||||
constexpr auto MakeStructArraySchema(const I&... info) {
|
||||
@@ -336,7 +370,7 @@ void ForEachStructSchema(
|
||||
if constexpr (HasNestedStruct<T, I...>) {
|
||||
S::ForEachNested(fn, info...);
|
||||
}
|
||||
fn(S::GetTypeString(info...), S::GetSchema(info...));
|
||||
fn(GetStructTypeString<T>(info...), S::GetSchema(info...));
|
||||
}
|
||||
|
||||
template <typename T, typename... I>
|
||||
@@ -397,8 +431,8 @@ class StructArrayBuffer {
|
||||
template <typename T, size_t N, typename... I>
|
||||
requires StructSerializable<T, I...>
|
||||
struct Struct<std::array<T, N>, I...> {
|
||||
static constexpr auto GetTypeString(const I&... info) {
|
||||
return MakeStructArrayTypeString<T, N>(info...);
|
||||
static constexpr auto GetTypeName(const I&... info) {
|
||||
return MakeStructArrayTypeName<T, N>(info...);
|
||||
}
|
||||
static constexpr size_t GetSize(const I&... info) {
|
||||
return N * GetStructSize<T>(info...);
|
||||
@@ -447,7 +481,7 @@ struct Struct<std::array<T, N>, I...> {
|
||||
*/
|
||||
template <>
|
||||
struct Struct<bool> {
|
||||
static constexpr std::string_view GetTypeString() { return "struct:bool"; }
|
||||
static constexpr std::string_view GetTypeName() { return "bool"; }
|
||||
static constexpr size_t GetSize() { return 1; }
|
||||
static constexpr std::string_view GetSchema() { return "bool value"; }
|
||||
static bool Unpack(std::span<const uint8_t> data) { return data[0]; }
|
||||
@@ -462,7 +496,7 @@ struct Struct<bool> {
|
||||
*/
|
||||
template <>
|
||||
struct Struct<uint8_t> {
|
||||
static constexpr std::string_view GetTypeString() { return "struct:uint8"; }
|
||||
static constexpr std::string_view GetTypeName() { return "uint8"; }
|
||||
static constexpr size_t GetSize() { return 1; }
|
||||
static constexpr std::string_view GetSchema() { return "uint8 value"; }
|
||||
static uint8_t Unpack(std::span<const uint8_t> data) { return data[0]; }
|
||||
@@ -475,7 +509,7 @@ struct Struct<uint8_t> {
|
||||
*/
|
||||
template <>
|
||||
struct Struct<int8_t> {
|
||||
static constexpr std::string_view GetTypeString() { return "struct:int8"; }
|
||||
static constexpr std::string_view GetTypeName() { return "int8"; }
|
||||
static constexpr size_t GetSize() { return 1; }
|
||||
static constexpr std::string_view GetSchema() { return "int8 value"; }
|
||||
static int8_t Unpack(std::span<const uint8_t> data) { return data[0]; }
|
||||
@@ -488,7 +522,7 @@ struct Struct<int8_t> {
|
||||
*/
|
||||
template <>
|
||||
struct Struct<uint16_t> {
|
||||
static constexpr std::string_view GetTypeString() { return "struct:uint16"; }
|
||||
static constexpr std::string_view GetTypeName() { return "uint16"; }
|
||||
static constexpr size_t GetSize() { return 2; }
|
||||
static constexpr std::string_view GetSchema() { return "uint16 value"; }
|
||||
static uint16_t Unpack(std::span<const uint8_t> data) {
|
||||
@@ -505,7 +539,7 @@ struct Struct<uint16_t> {
|
||||
*/
|
||||
template <>
|
||||
struct Struct<int16_t> {
|
||||
static constexpr std::string_view GetTypeString() { return "struct:int16"; }
|
||||
static constexpr std::string_view GetTypeName() { return "int16"; }
|
||||
static constexpr size_t GetSize() { return 2; }
|
||||
static constexpr std::string_view GetSchema() { return "int16 value"; }
|
||||
static int16_t Unpack(std::span<const uint8_t> data) {
|
||||
@@ -522,7 +556,7 @@ struct Struct<int16_t> {
|
||||
*/
|
||||
template <>
|
||||
struct Struct<uint32_t> {
|
||||
static constexpr std::string_view GetTypeString() { return "struct:uint32"; }
|
||||
static constexpr std::string_view GetTypeName() { return "uint32"; }
|
||||
static constexpr size_t GetSize() { return 4; }
|
||||
static constexpr std::string_view GetSchema() { return "uint32 value"; }
|
||||
static uint32_t Unpack(std::span<const uint8_t> data) {
|
||||
@@ -539,7 +573,7 @@ struct Struct<uint32_t> {
|
||||
*/
|
||||
template <>
|
||||
struct Struct<int32_t> {
|
||||
static constexpr std::string_view GetTypeString() { return "struct:int32"; }
|
||||
static constexpr std::string_view GetTypeName() { return "int32"; }
|
||||
static constexpr size_t GetSize() { return 4; }
|
||||
static constexpr std::string_view GetSchema() { return "int32 value"; }
|
||||
static int32_t Unpack(std::span<const uint8_t> data) {
|
||||
@@ -556,7 +590,7 @@ struct Struct<int32_t> {
|
||||
*/
|
||||
template <>
|
||||
struct Struct<uint64_t> {
|
||||
static constexpr std::string_view GetTypeString() { return "struct:uint64"; }
|
||||
static constexpr std::string_view GetTypeName() { return "uint64"; }
|
||||
static constexpr size_t GetSize() { return 8; }
|
||||
static constexpr std::string_view GetSchema() { return "uint64 value"; }
|
||||
static uint64_t Unpack(std::span<const uint8_t> data) {
|
||||
@@ -573,7 +607,7 @@ struct Struct<uint64_t> {
|
||||
*/
|
||||
template <>
|
||||
struct Struct<int64_t> {
|
||||
static constexpr std::string_view GetTypeString() { return "struct:int64"; }
|
||||
static constexpr std::string_view GetTypeName() { return "int64"; }
|
||||
static constexpr size_t GetSize() { return 8; }
|
||||
static constexpr std::string_view GetSchema() { return "int64 value"; }
|
||||
static int64_t Unpack(std::span<const uint8_t> data) {
|
||||
@@ -590,7 +624,7 @@ struct Struct<int64_t> {
|
||||
*/
|
||||
template <>
|
||||
struct Struct<float> {
|
||||
static constexpr std::string_view GetTypeString() { return "struct:float"; }
|
||||
static constexpr std::string_view GetTypeName() { return "float"; }
|
||||
static constexpr size_t GetSize() { return 4; }
|
||||
static constexpr std::string_view GetSchema() { return "float value"; }
|
||||
static float Unpack(std::span<const uint8_t> data) {
|
||||
@@ -607,7 +641,7 @@ struct Struct<float> {
|
||||
*/
|
||||
template <>
|
||||
struct Struct<double> {
|
||||
static constexpr std::string_view GetTypeString() { return "struct:double"; }
|
||||
static constexpr std::string_view GetTypeName() { return "double"; }
|
||||
static constexpr size_t GetSize() { return 8; }
|
||||
static constexpr std::string_view GetSchema() { return "double value"; }
|
||||
static double Unpack(std::span<const uint8_t> data) {
|
||||
|
||||
@@ -27,8 +27,8 @@ class DataLogTest {
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getTypeString() {
|
||||
return "struct:Thing";
|
||||
public String getTypeName() {
|
||||
return "Thing";
|
||||
}
|
||||
|
||||
@Override
|
||||
@@ -84,8 +84,8 @@ class DataLogTest {
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getTypeString() {
|
||||
return "struct:Thing";
|
||||
public String getTypeName() {
|
||||
return "Thing";
|
||||
}
|
||||
|
||||
@Override
|
||||
@@ -156,8 +156,8 @@ class DataLogTest {
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getTypeString() {
|
||||
return "struct:Thing";
|
||||
public String getTypeName() {
|
||||
return "Thing";
|
||||
}
|
||||
|
||||
@Override
|
||||
|
||||
@@ -39,7 +39,7 @@ struct Info2 {
|
||||
|
||||
template <>
|
||||
struct wpi::Struct<ThingA> {
|
||||
static constexpr std::string_view GetTypeString() { return "struct:ThingA"; }
|
||||
static constexpr std::string_view GetTypeName() { return "ThingA"; }
|
||||
static constexpr size_t GetSize() { return 1; }
|
||||
static constexpr std::string_view GetSchema() { return "uint8 value"; }
|
||||
static ThingA Unpack(std::span<const uint8_t> data) {
|
||||
@@ -52,8 +52,8 @@ struct wpi::Struct<ThingA> {
|
||||
|
||||
template <>
|
||||
struct wpi::Struct<ThingB, Info1> {
|
||||
static constexpr std::string_view GetTypeString(const Info1&) {
|
||||
return "struct:ThingB";
|
||||
static constexpr std::string_view GetTypeName(const Info1&) {
|
||||
return "ThingB";
|
||||
}
|
||||
static constexpr size_t GetSize(const Info1&) { return 1; }
|
||||
static constexpr std::string_view GetSchema(const Info1&) {
|
||||
@@ -69,7 +69,7 @@ struct wpi::Struct<ThingB, Info1> {
|
||||
|
||||
template <>
|
||||
struct wpi::Struct<ThingC> {
|
||||
static constexpr std::string_view GetTypeString() { return "struct:ThingC"; }
|
||||
static constexpr std::string_view GetTypeName() { return "ThingC"; }
|
||||
static constexpr size_t GetSize() { return 1; }
|
||||
static constexpr std::string_view GetSchema() { return "uint8 value"; }
|
||||
static ThingC Unpack(std::span<const uint8_t> data) {
|
||||
@@ -82,8 +82,8 @@ struct wpi::Struct<ThingC> {
|
||||
|
||||
template <>
|
||||
struct wpi::Struct<ThingC, Info1> {
|
||||
static constexpr std::string_view GetTypeString(const Info1&) {
|
||||
return "struct:ThingC";
|
||||
static constexpr std::string_view GetTypeName(const Info1&) {
|
||||
return "ThingC";
|
||||
}
|
||||
static constexpr size_t GetSize(const Info1&) { return 1; }
|
||||
static constexpr std::string_view GetSchema(const Info1&) {
|
||||
@@ -99,8 +99,8 @@ struct wpi::Struct<ThingC, Info1> {
|
||||
|
||||
template <>
|
||||
struct wpi::Struct<ThingC, Info2> {
|
||||
static constexpr std::string_view GetTypeString(const Info2&) {
|
||||
return "struct:ThingC";
|
||||
static constexpr std::string_view GetTypeName(const Info2&) {
|
||||
return "ThingC";
|
||||
}
|
||||
static constexpr size_t GetSize(const Info2&) { return 1; }
|
||||
static constexpr std::string_view GetSchema(const Info2&) {
|
||||
|
||||
Reference in New Issue
Block a user