[wpimath] Add protobuf/struct for trivial types (#5935)

This implements de/serialization for the types that aren't templated (SwerveDriveKinematics) in C++ or where there is no trivial way to go round-trip (Splines) for the messages.
This commit is contained in:
PJ Reiniger
2023-11-21 13:14:06 -05:00
committed by GitHub
parent 35744a036e
commit bb05e20247
158 changed files with 4266 additions and 4 deletions

View File

@@ -0,0 +1,33 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
#include "frc/controller/proto/ArmFeedforwardProto.h"
#include "controller.pb.h"
google::protobuf::Message* wpi::Protobuf<frc::ArmFeedforward>::New(
google::protobuf::Arena* arena) {
return google::protobuf::Arena::CreateMessage<
wpi::proto::ProtobufArmFeedforward>(arena);
}
frc::ArmFeedforward wpi::Protobuf<frc::ArmFeedforward>::Unpack(
const google::protobuf::Message& msg) {
auto m = static_cast<const wpi::proto::ProtobufArmFeedforward*>(&msg);
return frc::ArmFeedforward{
units::volt_t{m->ks()},
units::volt_t{m->kg()},
units::unit_t<frc::ArmFeedforward::kv_unit>{m->kv()},
units::unit_t<frc::ArmFeedforward::ka_unit>{m->ka()},
};
}
void wpi::Protobuf<frc::ArmFeedforward>::Pack(
google::protobuf::Message* msg, const frc::ArmFeedforward& value) {
auto m = static_cast<wpi::proto::ProtobufArmFeedforward*>(msg);
m->set_ks(value.kS.value());
m->set_kg(value.kG.value());
m->set_kv(value.kV.value());
m->set_ka(value.kA.value());
}

View File

@@ -0,0 +1,34 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
#include "frc/controller/proto/DifferentialDriveWheelVoltagesProto.h"
#include "controller.pb.h"
google::protobuf::Message* wpi::Protobuf<
frc::DifferentialDriveWheelVoltages>::New(google::protobuf::Arena* arena) {
return google::protobuf::Arena::CreateMessage<
wpi::proto::ProtobufDifferentialDriveWheelVoltages>(arena);
}
frc::DifferentialDriveWheelVoltages
wpi::Protobuf<frc::DifferentialDriveWheelVoltages>::Unpack(
const google::protobuf::Message& msg) {
auto m =
static_cast<const wpi::proto::ProtobufDifferentialDriveWheelVoltages*>(
&msg);
return frc::DifferentialDriveWheelVoltages{
units::volt_t{m->left()},
units::volt_t{m->right()},
};
}
void wpi::Protobuf<frc::DifferentialDriveWheelVoltages>::Pack(
google::protobuf::Message* msg,
const frc::DifferentialDriveWheelVoltages& value) {
auto m =
static_cast<wpi::proto::ProtobufDifferentialDriveWheelVoltages*>(msg);
m->set_left(value.left.value());
m->set_right(value.right.value());
}

View File

@@ -0,0 +1,33 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
#include "frc/controller/proto/ElevatorFeedforwardProto.h"
#include "controller.pb.h"
google::protobuf::Message* wpi::Protobuf<frc::ElevatorFeedforward>::New(
google::protobuf::Arena* arena) {
return google::protobuf::Arena::CreateMessage<
wpi::proto::ProtobufElevatorFeedforward>(arena);
}
frc::ElevatorFeedforward wpi::Protobuf<frc::ElevatorFeedforward>::Unpack(
const google::protobuf::Message& msg) {
auto m = static_cast<const wpi::proto::ProtobufElevatorFeedforward*>(&msg);
return frc::ElevatorFeedforward{
units::volt_t{m->ks()},
units::volt_t{m->kg()},
units::unit_t<frc::ElevatorFeedforward::kv_unit>{m->kv()},
units::unit_t<frc::ElevatorFeedforward::ka_unit>{m->ka()},
};
}
void wpi::Protobuf<frc::ElevatorFeedforward>::Pack(
google::protobuf::Message* msg, const frc::ElevatorFeedforward& value) {
auto m = static_cast<wpi::proto::ProtobufElevatorFeedforward*>(msg);
m->set_ks(value.kS());
m->set_kg(value.kG());
m->set_kv(value.kV());
m->set_ka(value.kA());
}

View File

@@ -0,0 +1,33 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
#include "frc/controller/struct/ArmFeedforwardStruct.h"
namespace {
constexpr size_t kKsOff = 0;
constexpr size_t kKgOff = kKsOff + 8;
constexpr size_t kKvOff = kKgOff + 8;
constexpr size_t kKaOff = kKvOff + 8;
} // namespace
using StructType = wpi::Struct<frc::ArmFeedforward>;
frc::ArmFeedforward StructType::Unpack(std::span<const uint8_t, kSize> data) {
return frc::ArmFeedforward{
units::volt_t{wpi::UnpackStruct<double, kKsOff>(data)},
units::volt_t{wpi::UnpackStruct<double, kKgOff>(data)},
units::unit_t<frc::ArmFeedforward::kv_unit>{
wpi::UnpackStruct<double, kKvOff>(data)},
units::unit_t<frc::ArmFeedforward::ka_unit>{
wpi::UnpackStruct<double, kKaOff>(data)},
};
}
void StructType::Pack(std::span<uint8_t, kSize> data,
const frc::ArmFeedforward& value) {
wpi::PackStruct<kKsOff>(data, value.kS());
wpi::PackStruct<kKgOff>(data, value.kG());
wpi::PackStruct<kKvOff>(data, value.kV());
wpi::PackStruct<kKaOff>(data, value.kA());
}

View File

@@ -0,0 +1,26 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
#include "frc/controller/struct/DifferentialDriveWheelVoltagesStruct.h"
namespace {
constexpr size_t kLeftOff = 0;
constexpr size_t kRightOff = kLeftOff + 8;
} // namespace
using StructType = wpi::Struct<frc::DifferentialDriveWheelVoltages>;
frc::DifferentialDriveWheelVoltages StructType::Unpack(
std::span<const uint8_t, kSize> 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,
const frc::DifferentialDriveWheelVoltages& value) {
wpi::PackStruct<kLeftOff>(data, value.left.value());
wpi::PackStruct<kRightOff>(data, value.right.value());
}

View File

@@ -0,0 +1,34 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
#include "frc/controller/struct/ElevatorFeedforwardStruct.h"
namespace {
constexpr size_t kKsOff = 0;
constexpr size_t kKgOff = kKsOff + 8;
constexpr size_t kKvOff = kKgOff + 8;
constexpr size_t kKaOff = kKvOff + 8;
} // namespace
using StructType = wpi::Struct<frc::ElevatorFeedforward>;
frc::ElevatorFeedforward StructType::Unpack(
std::span<const uint8_t, kSize> data) {
return frc::ElevatorFeedforward{
units::volt_t{wpi::UnpackStruct<double, kKsOff>(data)},
units::volt_t{wpi::UnpackStruct<double, kKgOff>(data)},
units::unit_t<frc::ElevatorFeedforward::kv_unit>{
wpi::UnpackStruct<double, kKvOff>(data)},
units::unit_t<frc::ElevatorFeedforward::ka_unit>{
wpi::UnpackStruct<double, kKaOff>(data)},
};
}
void StructType::Pack(std::span<uint8_t, kSize> data,
const frc::ElevatorFeedforward& value) {
wpi::PackStruct<kKsOff>(data, value.kS());
wpi::PackStruct<kKgOff>(data, value.kG());
wpi::PackStruct<kKvOff>(data, value.kV());
wpi::PackStruct<kKaOff>(data, value.kA());
}

View File

@@ -0,0 +1,31 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
#include "frc/kinematics/proto/ChassisSpeedsProto.h"
#include "kinematics.pb.h"
google::protobuf::Message* wpi::Protobuf<frc::ChassisSpeeds>::New(
google::protobuf::Arena* arena) {
return google::protobuf::Arena::CreateMessage<
wpi::proto::ProtobufChassisSpeeds>(arena);
}
frc::ChassisSpeeds wpi::Protobuf<frc::ChassisSpeeds>::Unpack(
const google::protobuf::Message& msg) {
auto m = static_cast<const wpi::proto::ProtobufChassisSpeeds*>(&msg);
return frc::ChassisSpeeds{
units::meters_per_second_t{m->vx()},
units::meters_per_second_t{m->vy()},
units::radians_per_second_t{m->omega()},
};
}
void wpi::Protobuf<frc::ChassisSpeeds>::Pack(google::protobuf::Message* msg,
const frc::ChassisSpeeds& value) {
auto m = static_cast<wpi::proto::ProtobufChassisSpeeds*>(msg);
m->set_vx(value.vx.value());
m->set_vy(value.vy.value());
m->set_omega(value.omega.value());
}

View File

@@ -0,0 +1,30 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
#include "frc/kinematics/proto/DifferentialDriveKinematicsProto.h"
#include "kinematics.pb.h"
google::protobuf::Message* wpi::Protobuf<frc::DifferentialDriveKinematics>::New(
google::protobuf::Arena* arena) {
return google::protobuf::Arena::CreateMessage<
wpi::proto::ProtobufDifferentialDriveKinematics>(arena);
}
frc::DifferentialDriveKinematics
wpi::Protobuf<frc::DifferentialDriveKinematics>::Unpack(
const google::protobuf::Message& msg) {
auto m =
static_cast<const wpi::proto::ProtobufDifferentialDriveKinematics*>(&msg);
return frc::DifferentialDriveKinematics{
units::meter_t{m->track_width()},
};
}
void wpi::Protobuf<frc::DifferentialDriveKinematics>::Pack(
google::protobuf::Message* msg,
const frc::DifferentialDriveKinematics& value) {
auto m = static_cast<wpi::proto::ProtobufDifferentialDriveKinematics*>(msg);
m->set_track_width(value.trackWidth.value());
}

View File

@@ -0,0 +1,32 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
#include "frc/kinematics/proto/DifferentialDriveWheelSpeedsProto.h"
#include "kinematics.pb.h"
google::protobuf::Message* wpi::Protobuf<
frc::DifferentialDriveWheelSpeeds>::New(google::protobuf::Arena* arena) {
return google::protobuf::Arena::CreateMessage<
wpi::proto::ProtobufDifferentialDriveWheelSpeeds>(arena);
}
frc::DifferentialDriveWheelSpeeds
wpi::Protobuf<frc::DifferentialDriveWheelSpeeds>::Unpack(
const google::protobuf::Message& msg) {
auto m = static_cast<const wpi::proto::ProtobufDifferentialDriveWheelSpeeds*>(
&msg);
return frc::DifferentialDriveWheelSpeeds{
units::meters_per_second_t{m->left()},
units::meters_per_second_t{m->right()},
};
}
void wpi::Protobuf<frc::DifferentialDriveWheelSpeeds>::Pack(
google::protobuf::Message* msg,
const frc::DifferentialDriveWheelSpeeds& value) {
auto m = static_cast<wpi::proto::ProtobufDifferentialDriveWheelSpeeds*>(msg);
m->set_left(value.left.value());
m->set_right(value.right.value());
}

View File

@@ -0,0 +1,33 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
#include "frc/kinematics/proto/MecanumDriveKinematicsProto.h"
#include "kinematics.pb.h"
google::protobuf::Message* wpi::Protobuf<frc::MecanumDriveKinematics>::New(
google::protobuf::Arena* arena) {
return google::protobuf::Arena::CreateMessage<
wpi::proto::ProtobufMecanumDriveKinematics>(arena);
}
frc::MecanumDriveKinematics wpi::Protobuf<frc::MecanumDriveKinematics>::Unpack(
const google::protobuf::Message& msg) {
auto m = static_cast<const wpi::proto::ProtobufMecanumDriveKinematics*>(&msg);
return frc::MecanumDriveKinematics{
wpi::UnpackProtobuf<frc::Translation2d>(m->front_left()),
wpi::UnpackProtobuf<frc::Translation2d>(m->front_right()),
wpi::UnpackProtobuf<frc::Translation2d>(m->rear_left()),
wpi::UnpackProtobuf<frc::Translation2d>(m->rear_right()),
};
}
void wpi::Protobuf<frc::MecanumDriveKinematics>::Pack(
google::protobuf::Message* msg, const frc::MecanumDriveKinematics& value) {
auto m = static_cast<wpi::proto::ProtobufMecanumDriveKinematics*>(msg);
wpi::PackProtobuf(m->mutable_front_left(), value.GetFrontLeftWheel());
wpi::PackProtobuf(m->mutable_front_right(), value.GetFrontRightWheel());
wpi::PackProtobuf(m->mutable_rear_left(), value.GetRearLeftWheel());
wpi::PackProtobuf(m->mutable_rear_right(), value.GetRearRightWheel());
}

View File

@@ -0,0 +1,36 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
#include "frc/kinematics/proto/MecanumDriveWheelPositionsProto.h"
#include "kinematics.pb.h"
google::protobuf::Message* wpi::Protobuf<frc::MecanumDriveWheelPositions>::New(
google::protobuf::Arena* arena) {
return google::protobuf::Arena::CreateMessage<
wpi::proto::ProtobufMecanumDriveWheelPositions>(arena);
}
frc::MecanumDriveWheelPositions
wpi::Protobuf<frc::MecanumDriveWheelPositions>::Unpack(
const google::protobuf::Message& msg) {
auto m =
static_cast<const wpi::proto::ProtobufMecanumDriveWheelPositions*>(&msg);
return frc::MecanumDriveWheelPositions{
units::meter_t{m->front_left()},
units::meter_t{m->front_right()},
units::meter_t{m->rear_left()},
units::meter_t{m->rear_right()},
};
}
void wpi::Protobuf<frc::MecanumDriveWheelPositions>::Pack(
google::protobuf::Message* msg,
const frc::MecanumDriveWheelPositions& value) {
auto m = static_cast<wpi::proto::ProtobufMecanumDriveWheelPositions*>(msg);
m->set_front_left(value.frontLeft.value());
m->set_front_right(value.frontRight.value());
m->set_rear_left(value.rearLeft.value());
m->set_rear_right(value.rearRight.value());
}

View File

@@ -0,0 +1,35 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
#include "frc/kinematics/proto/MecanumDriveWheelSpeedsProto.h"
#include "kinematics.pb.h"
google::protobuf::Message* wpi::Protobuf<frc::MecanumDriveWheelSpeeds>::New(
google::protobuf::Arena* arena) {
return google::protobuf::Arena::CreateMessage<
wpi::proto::ProtobufMecanumDriveWheelSpeeds>(arena);
}
frc::MecanumDriveWheelSpeeds
wpi::Protobuf<frc::MecanumDriveWheelSpeeds>::Unpack(
const google::protobuf::Message& msg) {
auto m =
static_cast<const wpi::proto::ProtobufMecanumDriveWheelSpeeds*>(&msg);
return frc::MecanumDriveWheelSpeeds{
units::meters_per_second_t{m->front_left()},
units::meters_per_second_t{m->front_right()},
units::meters_per_second_t{m->rear_left()},
units::meters_per_second_t{m->rear_right()},
};
}
void wpi::Protobuf<frc::MecanumDriveWheelSpeeds>::Pack(
google::protobuf::Message* msg, const frc::MecanumDriveWheelSpeeds& value) {
auto m = static_cast<wpi::proto::ProtobufMecanumDriveWheelSpeeds*>(msg);
m->set_front_left(value.frontLeft.value());
m->set_front_right(value.frontRight.value());
m->set_rear_left(value.rearLeft.value());
m->set_rear_right(value.rearRight.value());
}

View File

@@ -0,0 +1,29 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
#include "frc/kinematics/proto/SwerveModulePositionProto.h"
#include "kinematics.pb.h"
google::protobuf::Message* wpi::Protobuf<frc::SwerveModulePosition>::New(
google::protobuf::Arena* arena) {
return google::protobuf::Arena::CreateMessage<
wpi::proto::ProtobufSwerveModulePosition>(arena);
}
frc::SwerveModulePosition wpi::Protobuf<frc::SwerveModulePosition>::Unpack(
const google::protobuf::Message& msg) {
auto m = static_cast<const wpi::proto::ProtobufSwerveModulePosition*>(&msg);
return frc::SwerveModulePosition{
units::meter_t{m->distance()},
wpi::UnpackProtobuf<frc::Rotation2d>(m->angle()),
};
}
void wpi::Protobuf<frc::SwerveModulePosition>::Pack(
google::protobuf::Message* msg, const frc::SwerveModulePosition& value) {
auto m = static_cast<wpi::proto::ProtobufSwerveModulePosition*>(msg);
m->set_distance(value.distance.value());
wpi::PackProtobuf(m->mutable_angle(), value.angle);
}

View File

@@ -0,0 +1,29 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
#include "frc/kinematics/proto/SwerveModuleStateProto.h"
#include "kinematics.pb.h"
google::protobuf::Message* wpi::Protobuf<frc::SwerveModuleState>::New(
google::protobuf::Arena* arena) {
return google::protobuf::Arena::CreateMessage<
wpi::proto::ProtobufSwerveModuleState>(arena);
}
frc::SwerveModuleState wpi::Protobuf<frc::SwerveModuleState>::Unpack(
const google::protobuf::Message& msg) {
auto m = static_cast<const wpi::proto::ProtobufSwerveModuleState*>(&msg);
return frc::SwerveModuleState{
units::meters_per_second_t{m->speed()},
wpi::UnpackProtobuf<frc::Rotation2d>(m->angle()),
};
}
void wpi::Protobuf<frc::SwerveModuleState>::Pack(
google::protobuf::Message* msg, const frc::SwerveModuleState& value) {
auto m = static_cast<wpi::proto::ProtobufSwerveModuleState*>(msg);
m->set_speed(value.speed.value());
wpi::PackProtobuf(m->mutable_angle(), value.angle);
}

View File

@@ -0,0 +1,28 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
#include "frc/kinematics/struct/ChassisSpeedsStruct.h"
namespace {
constexpr size_t kVxOff = 0;
constexpr size_t kVyOff = kVxOff + 8;
constexpr size_t kOmegaOff = kVyOff + 8;
} // namespace
using StructType = wpi::Struct<frc::ChassisSpeeds>;
frc::ChassisSpeeds StructType::Unpack(std::span<const uint8_t, kSize> data) {
return frc::ChassisSpeeds{
units::meters_per_second_t{wpi::UnpackStruct<double, kVxOff>(data)},
units::meters_per_second_t{wpi::UnpackStruct<double, kVyOff>(data)},
units::radians_per_second_t{wpi::UnpackStruct<double, kOmegaOff>(data)},
};
}
void StructType::Pack(std::span<uint8_t, kSize> data,
const frc::ChassisSpeeds& value) {
wpi::PackStruct<kVxOff>(data, value.vx.value());
wpi::PackStruct<kVyOff>(data, value.vy.value());
wpi::PackStruct<kOmegaOff>(data, value.omega.value());
}

View File

@@ -0,0 +1,23 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
#include "frc/kinematics/struct/DifferentialDriveKinematicsStruct.h"
namespace {
constexpr size_t kTrackWidthOff = 0;
} // namespace
using StructType = wpi::Struct<frc::DifferentialDriveKinematics>;
frc::DifferentialDriveKinematics StructType::Unpack(
std::span<const uint8_t, kSize> data) {
return frc::DifferentialDriveKinematics{
units::meter_t{wpi::UnpackStruct<double, kTrackWidthOff>(data)},
};
}
void StructType::Pack(std::span<uint8_t, kSize> data,
const frc::DifferentialDriveKinematics& value) {
wpi::PackStruct<kTrackWidthOff>(data, value.trackWidth.value());
}

View File

@@ -0,0 +1,26 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
#include "frc/kinematics/struct/DifferentialDriveWheelSpeedsStruct.h"
namespace {
constexpr size_t kLeftOff = 0;
constexpr size_t kRightOff = kLeftOff + 8;
} // namespace
using StructType = wpi::Struct<frc::DifferentialDriveWheelSpeeds>;
frc::DifferentialDriveWheelSpeeds StructType::Unpack(
std::span<const uint8_t, kSize> data) {
return frc::DifferentialDriveWheelSpeeds{
units::meters_per_second_t{wpi::UnpackStruct<double, kLeftOff>(data)},
units::meters_per_second_t{wpi::UnpackStruct<double, kRightOff>(data)},
};
}
void StructType::Pack(std::span<uint8_t, kSize> data,
const frc::DifferentialDriveWheelSpeeds& value) {
wpi::PackStruct<kLeftOff>(data, value.left.value());
wpi::PackStruct<kRightOff>(data, value.right.value());
}

View File

@@ -0,0 +1,40 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
#include "frc/kinematics/struct/MecanumDriveKinematicsStruct.h"
namespace {
constexpr size_t kFrontLeftOff = 0;
constexpr size_t kFrontRightOff =
kFrontLeftOff + wpi::Struct<frc::Translation2d>::kSize;
constexpr size_t kRearLeftOff =
kFrontRightOff + wpi::Struct<frc::Translation2d>::kSize;
constexpr size_t kRearRightOff =
kRearLeftOff + wpi::Struct<frc::Translation2d>::kSize;
} // namespace
using StructType = wpi::Struct<frc::MecanumDriveKinematics>;
frc::MecanumDriveKinematics StructType::Unpack(
std::span<const uint8_t, kSize> data) {
return frc::MecanumDriveKinematics{
wpi::UnpackStruct<frc::Translation2d, kFrontLeftOff>(data),
wpi::UnpackStruct<frc::Translation2d, kFrontRightOff>(data),
wpi::UnpackStruct<frc::Translation2d, kRearLeftOff>(data),
wpi::UnpackStruct<frc::Translation2d, kRearRightOff>(data),
};
}
void StructType::Pack(std::span<uint8_t, kSize> data,
const frc::MecanumDriveKinematics& value) {
wpi::PackStruct<kFrontLeftOff>(data, value.GetFrontLeftWheel());
wpi::PackStruct<kFrontRightOff>(data, value.GetFrontRightWheel());
wpi::PackStruct<kRearLeftOff>(data, value.GetRearLeftWheel());
wpi::PackStruct<kRearRightOff>(data, value.GetRearRightWheel());
}
void StructType::ForEachNested(
std::invocable<std::string_view, std::string_view> auto fn) {
wpi::ForEachStructSchema<frc::Translation2d>(fn);
}

View File

@@ -0,0 +1,32 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
#include "frc/kinematics/struct/MecanumDriveWheelPositionsStruct.h"
namespace {
constexpr size_t kFrontLeftOff = 0;
constexpr size_t kFrontRightOff = kFrontLeftOff + 8;
constexpr size_t kRearLeftOff = kFrontRightOff + 8;
constexpr size_t kRearRightOff = kRearLeftOff + 8;
} // namespace
using StructType = wpi::Struct<frc::MecanumDriveWheelPositions>;
frc::MecanumDriveWheelPositions StructType::Unpack(
std::span<const uint8_t, kSize> data) {
return frc::MecanumDriveWheelPositions{
units::meter_t{wpi::UnpackStruct<double, kFrontLeftOff>(data)},
units::meter_t{wpi::UnpackStruct<double, kFrontRightOff>(data)},
units::meter_t{wpi::UnpackStruct<double, kRearLeftOff>(data)},
units::meter_t{wpi::UnpackStruct<double, kRearRightOff>(data)},
};
}
void StructType::Pack(std::span<uint8_t, kSize> data,
const frc::MecanumDriveWheelPositions& value) {
wpi::PackStruct<kFrontLeftOff>(data, value.frontLeft.value());
wpi::PackStruct<kFrontRightOff>(data, value.frontRight.value());
wpi::PackStruct<kRearLeftOff>(data, value.rearLeft.value());
wpi::PackStruct<kRearRightOff>(data, value.rearRight.value());
}

View File

@@ -0,0 +1,35 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
#include "frc/kinematics/struct/MecanumDriveWheelSpeedsStruct.h"
namespace {
constexpr size_t kFrontLeftOff = 0;
constexpr size_t kFrontRightOff = kFrontLeftOff + 8;
constexpr size_t kRearLeftOff = kFrontRightOff + 8;
constexpr size_t kRearRightOff = kRearLeftOff + 8;
} // namespace
using StructType = wpi::Struct<frc::MecanumDriveWheelSpeeds>;
frc::MecanumDriveWheelSpeeds StructType::Unpack(
std::span<const uint8_t, kSize> data) {
return frc::MecanumDriveWheelSpeeds{
units::meters_per_second_t{
wpi::UnpackStruct<double, kFrontLeftOff>(data)},
units::meters_per_second_t{
wpi::UnpackStruct<double, kFrontRightOff>(data)},
units::meters_per_second_t{wpi::UnpackStruct<double, kRearLeftOff>(data)},
units::meters_per_second_t{
wpi::UnpackStruct<double, kRearRightOff>(data)},
};
}
void StructType::Pack(std::span<uint8_t, kSize> data,
const frc::MecanumDriveWheelSpeeds& value) {
wpi::PackStruct<kFrontLeftOff>(data, value.frontLeft.value());
wpi::PackStruct<kFrontRightOff>(data, value.frontRight.value());
wpi::PackStruct<kRearLeftOff>(data, value.rearLeft.value());
wpi::PackStruct<kRearRightOff>(data, value.rearRight.value());
}

View File

@@ -0,0 +1,31 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
#include "frc/kinematics/struct/SwerveModulePositionStruct.h"
namespace {
constexpr size_t kDistanceOff = 0;
constexpr size_t kAngleOff = kDistanceOff + 8;
} // namespace
using StructType = wpi::Struct<frc::SwerveModulePosition>;
frc::SwerveModulePosition StructType::Unpack(
std::span<const uint8_t, kSize> data) {
return frc::SwerveModulePosition{
units::meter_t{wpi::UnpackStruct<double, kDistanceOff>(data)},
wpi::UnpackStruct<frc::Rotation2d, kAngleOff>(data),
};
}
void StructType::Pack(std::span<uint8_t, kSize> data,
const frc::SwerveModulePosition& value) {
wpi::PackStruct<kDistanceOff>(data, value.distance.value());
wpi::PackStruct<kAngleOff>(data, value.angle);
}
void StructType::ForEachNested(
std::invocable<std::string_view, std::string_view> auto fn) {
wpi::ForEachStructSchema<frc::Rotation2d>(fn);
}

View File

@@ -0,0 +1,31 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
#include "frc/kinematics/struct/SwerveModuleStateStruct.h"
namespace {
constexpr size_t kSpeedOff = 0;
constexpr size_t kAngleOff = kSpeedOff + 8;
} // namespace
using StructType = wpi::Struct<frc::SwerveModuleState>;
frc::SwerveModuleState StructType::Unpack(
std::span<const uint8_t, kSize> data) {
return frc::SwerveModuleState{
units::meters_per_second_t{wpi::UnpackStruct<double, kSpeedOff>(data)},
wpi::UnpackStruct<frc::Rotation2d, kAngleOff>(data),
};
}
void StructType::Pack(std::span<uint8_t, kSize> data,
const frc::SwerveModuleState& value) {
wpi::PackStruct<kSpeedOff>(data, value.speed.value());
wpi::PackStruct<kAngleOff>(data, value.angle);
}
void StructType::ForEachNested(
std::invocable<std::string_view, std::string_view> auto fn) {
wpi::ForEachStructSchema<frc::Rotation2d>(fn);
}

View File

@@ -0,0 +1,35 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
#include "frc/system/plant/proto/DCMotorProto.h"
#include "plant.pb.h"
google::protobuf::Message* wpi::Protobuf<frc::DCMotor>::New(
google::protobuf::Arena* arena) {
return google::protobuf::Arena::CreateMessage<wpi::proto::ProtobufDCMotor>(
arena);
}
frc::DCMotor wpi::Protobuf<frc::DCMotor>::Unpack(
const google::protobuf::Message& msg) {
auto m = static_cast<const wpi::proto::ProtobufDCMotor*>(&msg);
return frc::DCMotor{
units::volt_t{m->nominal_voltage()},
units::newton_meter_t{m->stall_torque()},
units::ampere_t{m->stall_current()},
units::ampere_t{m->free_current()},
units::radians_per_second_t{m->free_speed()},
};
}
void wpi::Protobuf<frc::DCMotor>::Pack(google::protobuf::Message* msg,
const frc::DCMotor& value) {
auto m = static_cast<wpi::proto::ProtobufDCMotor*>(msg);
m->set_nominal_voltage(value.nominalVoltage.value());
m->set_stall_torque(value.stallTorque.value());
m->set_stall_current(value.stallCurrent.value());
m->set_free_current(value.freeCurrent.value());
m->set_free_speed(value.freeSpeed.value());
}

View File

@@ -0,0 +1,35 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
#include "frc/system/plant/struct/DCMotorStruct.h"
namespace {
constexpr size_t kNominalVoltageOff = 0;
constexpr size_t kStallTorqueOff = kNominalVoltageOff + 8;
constexpr size_t kStallCurrentOff = kStallTorqueOff + 8;
constexpr size_t kFreeCurrentOff = kStallCurrentOff + 8;
constexpr size_t kFreeSpeedOff = kFreeCurrentOff + 8;
} // namespace
using StructType = wpi::Struct<frc::DCMotor>;
frc::DCMotor StructType::Unpack(std::span<const uint8_t, kSize> data) {
return frc::DCMotor{
units::volt_t{wpi::UnpackStruct<double, kNominalVoltageOff>(data)},
units::newton_meter_t{wpi::UnpackStruct<double, kStallTorqueOff>(data)},
units::ampere_t{wpi::UnpackStruct<double, kStallCurrentOff>(data)},
units::ampere_t{wpi::UnpackStruct<double, kFreeCurrentOff>(data)},
units::radians_per_second_t{
wpi::UnpackStruct<double, kFreeSpeedOff>(data)},
};
}
void StructType::Pack(std::span<uint8_t, kSize> 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());
wpi::PackStruct<kFreeCurrentOff>(data, value.freeCurrent.value());
wpi::PackStruct<kFreeSpeedOff>(data, value.freeSpeed.value());
}

View File

@@ -0,0 +1,33 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
#include "frc/trajectory/proto/TrajectoryProto.h"
#include "trajectory.pb.h"
google::protobuf::Message* wpi::Protobuf<frc::Trajectory>::New(
google::protobuf::Arena* arena) {
return google::protobuf::Arena::CreateMessage<wpi::proto::ProtobufTrajectory>(
arena);
}
frc::Trajectory wpi::Protobuf<frc::Trajectory>::Unpack(
const google::protobuf::Message& msg) {
auto m = static_cast<const wpi::proto::ProtobufTrajectory*>(&msg);
std::vector<frc::Trajectory::State> states;
states.reserve(m->states().size());
for (const auto& protoState : m->states()) {
states.push_back(wpi::UnpackProtobuf<frc::Trajectory::State>(protoState));
}
return frc::Trajectory{states};
}
void wpi::Protobuf<frc::Trajectory>::Pack(google::protobuf::Message* msg,
const frc::Trajectory& value) {
auto m = static_cast<wpi::proto::ProtobufTrajectory*>(msg);
m->mutable_states()->Reserve(value.States().size());
for (const auto& state : value.States()) {
wpi::PackProtobuf(m->add_states(), state);
}
}

View File

@@ -0,0 +1,35 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
#include "frc/trajectory/proto/TrajectoryStateProto.h"
#include "trajectory.pb.h"
google::protobuf::Message* wpi::Protobuf<frc::Trajectory::State>::New(
google::protobuf::Arena* arena) {
return google::protobuf::Arena::CreateMessage<
wpi::proto::ProtobufTrajectoryState>(arena);
}
frc::Trajectory::State wpi::Protobuf<frc::Trajectory::State>::Unpack(
const google::protobuf::Message& msg) {
auto m = static_cast<const wpi::proto::ProtobufTrajectoryState*>(&msg);
return frc::Trajectory::State{
units::second_t{m->time()},
units::meters_per_second_t{m->velocity()},
units::meters_per_second_squared_t{m->acceleration()},
wpi::UnpackProtobuf<frc::Pose2d>(m->pose()),
units::curvature_t{m->curvature()},
};
}
void wpi::Protobuf<frc::Trajectory::State>::Pack(
google::protobuf::Message* msg, const frc::Trajectory::State& value) {
auto m = static_cast<wpi::proto::ProtobufTrajectoryState*>(msg);
m->set_time(value.t.value());
m->set_velocity(value.velocity.value());
m->set_acceleration(value.acceleration.value());
wpi::PackProtobuf(m->mutable_pose(), value.pose);
m->set_curvature(value.curvature.value());
}