15 return "struct:SwerveModuleState";
18 return 8 + wpi::GetStructSize<frc::Rotation2d>();
21 return "double speed;Rotation2d angle";
25 static void Pack(std::span<uint8_t> data,
28 std::invocable<std::string_view, std::string_view>
auto fn) {
29 wpi::ForEachStructSchema<frc::Rotation2d>(fn);
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
Specifies that a struct type has nested struct declarations.
Definition: Struct.h:119
Specifies that a type is capable of raw struct serialization and deserialization.
Definition: Struct.h:68
basic_string_view< char > string_view
Definition: core.h:501
Definition: ntcore_cpp.h:26
Represents the state of one swerve module.
Definition: SwerveModuleState.h:18
static void Pack(std::span< uint8_t > data, const frc::SwerveModuleState &value)
static void ForEachNested(std::invocable< std::string_view, std::string_view > auto fn)
Definition: SwerveModuleStateStruct.h:27
static frc::SwerveModuleState Unpack(std::span< const uint8_t > data)
static constexpr std::string_view GetTypeString()
Definition: SwerveModuleStateStruct.h:14
static constexpr std::string_view GetSchema()
Definition: SwerveModuleStateStruct.h:20
static constexpr size_t GetSize()
Definition: SwerveModuleStateStruct.h:17