mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +00:00
[wpiutil] Change C++ protobuf to nanopb (#7309)
The Google C++ protobuf implementation has issues with dynamic linkage across DLL boundaries because it uses global variables. It also has a compile-time dependency because the protoc version must exactly match the libprotobuf version. Using nanopb with a customized generator fixes both of these issues. Co-authored-by: Gold856 <117957790+Gold856@users.noreply.github.com>
This commit is contained in:
@@ -4,31 +4,33 @@
|
||||
|
||||
#include "frc/controller/proto/ArmFeedforwardProto.h"
|
||||
|
||||
#include <wpi/ProtoHelper.h>
|
||||
#include <optional>
|
||||
|
||||
#include "controller.pb.h"
|
||||
#include "wpimath/protobuf/controller.npb.h"
|
||||
|
||||
google::protobuf::Message* wpi::Protobuf<frc::ArmFeedforward>::New(
|
||||
google::protobuf::Arena* arena) {
|
||||
return wpi::CreateMessage<wpi::proto::ProtobufArmFeedforward>(arena);
|
||||
}
|
||||
std::optional<frc::ArmFeedforward> wpi::Protobuf<frc::ArmFeedforward>::Unpack(
|
||||
InputStream& stream) {
|
||||
wpi_proto_ProtobufArmFeedforward msg;
|
||||
if (!stream.Decode(msg)) {
|
||||
return {};
|
||||
}
|
||||
|
||||
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()},
|
||||
units::volt_t{msg.ks},
|
||||
units::volt_t{msg.kg},
|
||||
units::unit_t<frc::ArmFeedforward::kv_unit>{msg.kv},
|
||||
units::unit_t<frc::ArmFeedforward::ka_unit>{msg.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.GetKs().value());
|
||||
m->set_kg(value.GetKg().value());
|
||||
m->set_kv(value.GetKv().value());
|
||||
m->set_ka(value.GetKa().value());
|
||||
bool wpi::Protobuf<frc::ArmFeedforward>::Pack(
|
||||
OutputStream& stream, const frc::ArmFeedforward& value) {
|
||||
wpi_proto_ProtobufArmFeedforward msg{
|
||||
.ks = value.GetKs().value(),
|
||||
.kg = value.GetKg().value(),
|
||||
.kv = value.GetKv().value(),
|
||||
.ka = value.GetKa().value(),
|
||||
.dt = 0,
|
||||
};
|
||||
return stream.Encode(msg);
|
||||
}
|
||||
|
||||
@@ -4,33 +4,30 @@
|
||||
|
||||
#include "frc/controller/proto/DifferentialDriveFeedforwardProto.h"
|
||||
|
||||
#include <wpi/ProtoHelper.h>
|
||||
#include "wpimath/protobuf/controller.npb.h"
|
||||
|
||||
#include "controller.pb.h"
|
||||
std::optional<frc::DifferentialDriveFeedforward>
|
||||
wpi::Protobuf<frc::DifferentialDriveFeedforward>::Unpack(InputStream& stream) {
|
||||
wpi_proto_ProtobufDifferentialDriveFeedforward msg;
|
||||
if (!stream.Decode(msg)) {
|
||||
return {};
|
||||
}
|
||||
|
||||
google::protobuf::Message* wpi::Protobuf<
|
||||
frc::DifferentialDriveFeedforward>::New(google::protobuf::Arena* arena) {
|
||||
return wpi::CreateMessage<wpi::proto::ProtobufDifferentialDriveFeedforward>(
|
||||
arena);
|
||||
return frc::DifferentialDriveFeedforward{
|
||||
decltype(1_V / 1_mps){msg.kv_linear},
|
||||
decltype(1_V / 1_mps_sq){msg.ka_linear},
|
||||
decltype(1_V / 1_mps){msg.kv_angular},
|
||||
decltype(1_V / 1_mps_sq){msg.ka_angular},
|
||||
};
|
||||
}
|
||||
|
||||
frc::DifferentialDriveFeedforward
|
||||
wpi::Protobuf<frc::DifferentialDriveFeedforward>::Unpack(
|
||||
const google::protobuf::Message& msg) {
|
||||
auto m = static_cast<const wpi::proto::ProtobufDifferentialDriveFeedforward*>(
|
||||
&msg);
|
||||
return {decltype(1_V / 1_mps){m->kv_linear()},
|
||||
decltype(1_V / 1_mps_sq){m->ka_linear()},
|
||||
decltype(1_V / 1_mps){m->kv_angular()},
|
||||
decltype(1_V / 1_mps_sq){m->ka_angular()}};
|
||||
}
|
||||
|
||||
void wpi::Protobuf<frc::DifferentialDriveFeedforward>::Pack(
|
||||
google::protobuf::Message* msg,
|
||||
const frc::DifferentialDriveFeedforward& value) {
|
||||
auto m = static_cast<wpi::proto::ProtobufDifferentialDriveFeedforward*>(msg);
|
||||
m->set_kv_linear(value.m_kVLinear.value());
|
||||
m->set_ka_linear(value.m_kALinear.value());
|
||||
m->set_kv_angular(value.m_kVAngular.value());
|
||||
m->set_ka_angular(value.m_kAAngular.value());
|
||||
bool wpi::Protobuf<frc::DifferentialDriveFeedforward>::Pack(
|
||||
OutputStream& stream, const frc::DifferentialDriveFeedforward& value) {
|
||||
wpi_proto_ProtobufDifferentialDriveFeedforward msg{
|
||||
.kv_linear = value.m_kVLinear.value(),
|
||||
.ka_linear = value.m_kALinear.value(),
|
||||
.kv_angular = value.m_kVAngular.value(),
|
||||
.ka_angular = value.m_kAAngular.value(),
|
||||
};
|
||||
return stream.Encode(msg);
|
||||
}
|
||||
|
||||
@@ -4,33 +4,28 @@
|
||||
|
||||
#include "frc/controller/proto/DifferentialDriveWheelVoltagesProto.h"
|
||||
|
||||
#include <wpi/ProtoHelper.h>
|
||||
#include <optional>
|
||||
|
||||
#include "controller.pb.h"
|
||||
#include "wpimath/protobuf/controller.npb.h"
|
||||
|
||||
google::protobuf::Message* wpi::Protobuf<
|
||||
frc::DifferentialDriveWheelVoltages>::New(google::protobuf::Arena* arena) {
|
||||
return wpi::CreateMessage<wpi::proto::ProtobufDifferentialDriveWheelVoltages>(
|
||||
arena);
|
||||
}
|
||||
std::optional<frc::DifferentialDriveWheelVoltages> wpi::Protobuf<
|
||||
frc::DifferentialDriveWheelVoltages>::Unpack(InputStream& stream) {
|
||||
wpi_proto_ProtobufDifferentialDriveWheelVoltages msg;
|
||||
if (!stream.Decode(msg)) {
|
||||
return {};
|
||||
}
|
||||
|
||||
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()},
|
||||
units::volt_t{msg.left},
|
||||
units::volt_t{msg.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());
|
||||
bool wpi::Protobuf<frc::DifferentialDriveWheelVoltages>::Pack(
|
||||
OutputStream& stream, const frc::DifferentialDriveWheelVoltages& value) {
|
||||
wpi_proto_ProtobufDifferentialDriveWheelVoltages msg{
|
||||
.left = value.left.value(),
|
||||
.right = value.right.value(),
|
||||
};
|
||||
return stream.Encode(msg);
|
||||
}
|
||||
|
||||
@@ -4,31 +4,33 @@
|
||||
|
||||
#include "frc/controller/proto/ElevatorFeedforwardProto.h"
|
||||
|
||||
#include <wpi/ProtoHelper.h>
|
||||
#include <optional>
|
||||
|
||||
#include "controller.pb.h"
|
||||
#include "wpimath/protobuf/controller.npb.h"
|
||||
|
||||
google::protobuf::Message* wpi::Protobuf<frc::ElevatorFeedforward>::New(
|
||||
google::protobuf::Arena* arena) {
|
||||
return wpi::CreateMessage<wpi::proto::ProtobufElevatorFeedforward>(arena);
|
||||
}
|
||||
std::optional<frc::ElevatorFeedforward>
|
||||
wpi::Protobuf<frc::ElevatorFeedforward>::Unpack(InputStream& stream) {
|
||||
wpi_proto_ProtobufElevatorFeedforward msg;
|
||||
if (!stream.Decode(msg)) {
|
||||
return {};
|
||||
}
|
||||
|
||||
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()},
|
||||
units::volt_t{msg.ks},
|
||||
units::volt_t{msg.kg},
|
||||
units::unit_t<frc::ElevatorFeedforward::kv_unit>{msg.kv},
|
||||
units::unit_t<frc::ElevatorFeedforward::ka_unit>{msg.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.GetKs().value());
|
||||
m->set_kg(value.GetKg().value());
|
||||
m->set_kv(value.GetKv().value());
|
||||
m->set_ka(value.GetKa().value());
|
||||
bool wpi::Protobuf<frc::ElevatorFeedforward>::Pack(
|
||||
OutputStream& stream, const frc::ElevatorFeedforward& value) {
|
||||
wpi_proto_ProtobufElevatorFeedforward msg{
|
||||
.ks = value.GetKs().value(),
|
||||
.kg = value.GetKg().value(),
|
||||
.kv = value.GetKv().value(),
|
||||
.ka = value.GetKa().value(),
|
||||
.dt = 0,
|
||||
};
|
||||
return stream.Encode(msg);
|
||||
}
|
||||
|
||||
@@ -4,29 +4,42 @@
|
||||
|
||||
#include "frc/geometry/proto/Ellipse2dProto.h"
|
||||
|
||||
#include <wpi/ProtoHelper.h>
|
||||
#include <wpi/protobuf/ProtobufCallbacks.h>
|
||||
|
||||
#include "geometry2d.pb.h"
|
||||
#include "wpimath/protobuf/geometry2d.npb.h"
|
||||
|
||||
google::protobuf::Message* wpi::Protobuf<frc::Ellipse2d>::New(
|
||||
google::protobuf::Arena* arena) {
|
||||
return wpi::CreateMessage<wpi::proto::ProtobufEllipse2d>(arena);
|
||||
}
|
||||
std::optional<frc::Ellipse2d> wpi::Protobuf<frc::Ellipse2d>::Unpack(
|
||||
InputStream& stream) {
|
||||
wpi::UnpackCallback<frc::Pose2d> pose;
|
||||
wpi_proto_ProtobufEllipse2d msg{
|
||||
.center = pose.Callback(),
|
||||
.xSemiAxis = 0,
|
||||
.ySemiAxis = 0,
|
||||
};
|
||||
if (!stream.Decode(msg)) {
|
||||
return {};
|
||||
}
|
||||
|
||||
auto ipose = pose.Items();
|
||||
|
||||
if (ipose.empty()) {
|
||||
return {};
|
||||
}
|
||||
|
||||
frc::Ellipse2d wpi::Protobuf<frc::Ellipse2d>::Unpack(
|
||||
const google::protobuf::Message& msg) {
|
||||
auto m = static_cast<const wpi::proto::ProtobufEllipse2d*>(&msg);
|
||||
return frc::Ellipse2d{
|
||||
wpi::UnpackProtobuf<frc::Pose2d>(m->wpi_center()),
|
||||
units::meter_t{m->xsemiaxis()},
|
||||
units::meter_t{m->ysemiaxis()},
|
||||
ipose[0],
|
||||
units::meter_t{msg.xSemiAxis},
|
||||
units::meter_t{msg.ySemiAxis},
|
||||
};
|
||||
}
|
||||
|
||||
void wpi::Protobuf<frc::Ellipse2d>::Pack(google::protobuf::Message* msg,
|
||||
bool wpi::Protobuf<frc::Ellipse2d>::Pack(OutputStream& stream,
|
||||
const frc::Ellipse2d& value) {
|
||||
auto m = static_cast<wpi::proto::ProtobufEllipse2d*>(msg);
|
||||
wpi::PackProtobuf(m->mutable_center(), value.Center());
|
||||
m->set_xsemiaxis(value.XSemiAxis().value());
|
||||
m->set_ysemiaxis(value.YSemiAxis().value());
|
||||
wpi::PackCallback pose{&value.Center()};
|
||||
wpi_proto_ProtobufEllipse2d msg{
|
||||
.center = pose.Callback(),
|
||||
.xSemiAxis = value.XSemiAxis().value(),
|
||||
.ySemiAxis = value.YSemiAxis().value(),
|
||||
};
|
||||
return stream.Encode(msg);
|
||||
}
|
||||
|
||||
@@ -4,27 +4,42 @@
|
||||
|
||||
#include "frc/geometry/proto/Pose2dProto.h"
|
||||
|
||||
#include <wpi/ProtoHelper.h>
|
||||
#include <wpi/protobuf/ProtobufCallbacks.h>
|
||||
|
||||
#include "geometry2d.pb.h"
|
||||
#include "wpimath/protobuf/geometry2d.npb.h"
|
||||
|
||||
google::protobuf::Message* wpi::Protobuf<frc::Pose2d>::New(
|
||||
google::protobuf::Arena* arena) {
|
||||
return wpi::CreateMessage<wpi::proto::ProtobufPose2d>(arena);
|
||||
}
|
||||
std::optional<frc::Pose2d> wpi::Protobuf<frc::Pose2d>::Unpack(
|
||||
InputStream& stream) {
|
||||
wpi::UnpackCallback<frc::Translation2d> tsln;
|
||||
wpi::UnpackCallback<frc::Rotation2d> rot;
|
||||
wpi_proto_ProtobufPose2d msg{
|
||||
.translation = tsln.Callback(),
|
||||
.rotation = rot.Callback(),
|
||||
};
|
||||
if (!stream.Decode(msg)) {
|
||||
return {};
|
||||
}
|
||||
|
||||
auto itsln = tsln.Items();
|
||||
auto irot = rot.Items();
|
||||
|
||||
if (itsln.empty() || irot.empty()) {
|
||||
return {};
|
||||
}
|
||||
|
||||
frc::Pose2d wpi::Protobuf<frc::Pose2d>::Unpack(
|
||||
const google::protobuf::Message& msg) {
|
||||
auto m = static_cast<const wpi::proto::ProtobufPose2d*>(&msg);
|
||||
return frc::Pose2d{
|
||||
wpi::UnpackProtobuf<frc::Translation2d>(m->wpi_translation()),
|
||||
wpi::UnpackProtobuf<frc::Rotation2d>(m->wpi_rotation()),
|
||||
itsln[0],
|
||||
irot[0],
|
||||
};
|
||||
}
|
||||
|
||||
void wpi::Protobuf<frc::Pose2d>::Pack(google::protobuf::Message* msg,
|
||||
bool wpi::Protobuf<frc::Pose2d>::Pack(OutputStream& stream,
|
||||
const frc::Pose2d& value) {
|
||||
auto m = static_cast<wpi::proto::ProtobufPose2d*>(msg);
|
||||
wpi::PackProtobuf(m->mutable_translation(), value.Translation());
|
||||
wpi::PackProtobuf(m->mutable_rotation(), value.Rotation());
|
||||
wpi::PackCallback tsln{&value.Translation()};
|
||||
wpi::PackCallback rot{&value.Rotation()};
|
||||
wpi_proto_ProtobufPose2d msg{
|
||||
.translation = tsln.Callback(),
|
||||
.rotation = rot.Callback(),
|
||||
};
|
||||
return stream.Encode(msg);
|
||||
}
|
||||
|
||||
@@ -4,27 +4,44 @@
|
||||
|
||||
#include "frc/geometry/proto/Pose3dProto.h"
|
||||
|
||||
#include <wpi/ProtoHelper.h>
|
||||
#include <wpi/protobuf/Protobuf.h>
|
||||
#include <wpi/protobuf/ProtobufCallbacks.h>
|
||||
|
||||
#include "geometry3d.pb.h"
|
||||
#include "frc/geometry/Pose3d.h"
|
||||
#include "wpimath/protobuf/geometry3d.npb.h"
|
||||
|
||||
google::protobuf::Message* wpi::Protobuf<frc::Pose3d>::New(
|
||||
google::protobuf::Arena* arena) {
|
||||
return wpi::CreateMessage<wpi::proto::ProtobufPose3d>(arena);
|
||||
}
|
||||
std::optional<frc::Pose3d> wpi::Protobuf<frc::Pose3d>::Unpack(
|
||||
InputStream& stream) {
|
||||
wpi::UnpackCallback<frc::Translation3d> tsln;
|
||||
wpi::UnpackCallback<frc::Rotation3d> rot;
|
||||
wpi_proto_ProtobufPose3d msg{
|
||||
.translation = tsln.Callback(),
|
||||
.rotation = rot.Callback(),
|
||||
};
|
||||
if (!stream.Decode(msg)) {
|
||||
return {};
|
||||
}
|
||||
|
||||
auto itsln = tsln.Items();
|
||||
auto irot = rot.Items();
|
||||
|
||||
if (itsln.empty() || irot.empty()) {
|
||||
return {};
|
||||
}
|
||||
|
||||
frc::Pose3d wpi::Protobuf<frc::Pose3d>::Unpack(
|
||||
const google::protobuf::Message& msg) {
|
||||
auto m = static_cast<const wpi::proto::ProtobufPose3d*>(&msg);
|
||||
return frc::Pose3d{
|
||||
wpi::UnpackProtobuf<frc::Translation3d>(m->wpi_translation()),
|
||||
wpi::UnpackProtobuf<frc::Rotation3d>(m->wpi_rotation()),
|
||||
itsln[0],
|
||||
irot[0],
|
||||
};
|
||||
}
|
||||
|
||||
void wpi::Protobuf<frc::Pose3d>::Pack(google::protobuf::Message* msg,
|
||||
bool wpi::Protobuf<frc::Pose3d>::Pack(OutputStream& stream,
|
||||
const frc::Pose3d& value) {
|
||||
auto m = static_cast<wpi::proto::ProtobufPose3d*>(msg);
|
||||
wpi::PackProtobuf(m->mutable_translation(), value.Translation());
|
||||
wpi::PackProtobuf(m->mutable_rotation(), value.Rotation());
|
||||
wpi::PackCallback tsln{&value.Translation()};
|
||||
wpi::PackCallback rot{&value.Rotation()};
|
||||
wpi_proto_ProtobufPose3d msg{
|
||||
.translation = tsln.Callback(),
|
||||
.rotation = rot.Callback(),
|
||||
};
|
||||
return stream.Encode(msg);
|
||||
}
|
||||
|
||||
@@ -4,31 +4,30 @@
|
||||
|
||||
#include "frc/geometry/proto/QuaternionProto.h"
|
||||
|
||||
#include <wpi/ProtoHelper.h>
|
||||
#include "wpimath/protobuf/geometry3d.npb.h"
|
||||
|
||||
#include "geometry3d.pb.h"
|
||||
std::optional<frc::Quaternion> wpi::Protobuf<frc::Quaternion>::Unpack(
|
||||
InputStream& stream) {
|
||||
wpi_proto_ProtobufQuaternion msg;
|
||||
if (!stream.Decode(msg)) {
|
||||
return {};
|
||||
}
|
||||
|
||||
google::protobuf::Message* wpi::Protobuf<frc::Quaternion>::New(
|
||||
google::protobuf::Arena* arena) {
|
||||
return wpi::CreateMessage<wpi::proto::ProtobufQuaternion>(arena);
|
||||
}
|
||||
|
||||
frc::Quaternion wpi::Protobuf<frc::Quaternion>::Unpack(
|
||||
const google::protobuf::Message& msg) {
|
||||
auto m = static_cast<const wpi::proto::ProtobufQuaternion*>(&msg);
|
||||
return frc::Quaternion{
|
||||
m->w(),
|
||||
m->x(),
|
||||
m->y(),
|
||||
m->z(),
|
||||
msg.w,
|
||||
msg.x,
|
||||
msg.y,
|
||||
msg.z,
|
||||
};
|
||||
}
|
||||
|
||||
void wpi::Protobuf<frc::Quaternion>::Pack(google::protobuf::Message* msg,
|
||||
bool wpi::Protobuf<frc::Quaternion>::Pack(OutputStream& stream,
|
||||
const frc::Quaternion& value) {
|
||||
auto m = static_cast<wpi::proto::ProtobufQuaternion*>(msg);
|
||||
m->set_w(value.W());
|
||||
m->set_x(value.X());
|
||||
m->set_y(value.Y());
|
||||
m->set_z(value.Z());
|
||||
wpi_proto_ProtobufQuaternion msg{
|
||||
.w = value.W(),
|
||||
.x = value.X(),
|
||||
.y = value.Y(),
|
||||
.z = value.Z(),
|
||||
};
|
||||
return stream.Encode(msg);
|
||||
}
|
||||
|
||||
@@ -4,29 +4,42 @@
|
||||
|
||||
#include "frc/geometry/proto/Rectangle2dProto.h"
|
||||
|
||||
#include <wpi/ProtoHelper.h>
|
||||
#include <wpi/protobuf/ProtobufCallbacks.h>
|
||||
|
||||
#include "geometry2d.pb.h"
|
||||
#include "wpimath/protobuf/geometry2d.npb.h"
|
||||
|
||||
google::protobuf::Message* wpi::Protobuf<frc::Rectangle2d>::New(
|
||||
google::protobuf::Arena* arena) {
|
||||
return wpi::CreateMessage<wpi::proto::ProtobufRectangle2d>(arena);
|
||||
}
|
||||
std::optional<frc::Rectangle2d> wpi::Protobuf<frc::Rectangle2d>::Unpack(
|
||||
InputStream& stream) {
|
||||
wpi::UnpackCallback<frc::Pose2d> pose;
|
||||
wpi_proto_ProtobufRectangle2d msg{
|
||||
.center = pose.Callback(),
|
||||
.xWidth = 0,
|
||||
.yWidth = 0,
|
||||
};
|
||||
if (!stream.Decode(msg)) {
|
||||
return {};
|
||||
}
|
||||
|
||||
auto ipose = pose.Items();
|
||||
|
||||
if (ipose.empty()) {
|
||||
return {};
|
||||
}
|
||||
|
||||
frc::Rectangle2d wpi::Protobuf<frc::Rectangle2d>::Unpack(
|
||||
const google::protobuf::Message& msg) {
|
||||
auto m = static_cast<const wpi::proto::ProtobufRectangle2d*>(&msg);
|
||||
return frc::Rectangle2d{
|
||||
wpi::UnpackProtobuf<frc::Pose2d>(m->wpi_center()),
|
||||
units::meter_t{m->xwidth()},
|
||||
units::meter_t{m->ywidth()},
|
||||
ipose[0],
|
||||
units::meter_t{msg.xWidth},
|
||||
units::meter_t{msg.yWidth},
|
||||
};
|
||||
}
|
||||
|
||||
void wpi::Protobuf<frc::Rectangle2d>::Pack(google::protobuf::Message* msg,
|
||||
bool wpi::Protobuf<frc::Rectangle2d>::Pack(OutputStream& stream,
|
||||
const frc::Rectangle2d& value) {
|
||||
auto m = static_cast<wpi::proto::ProtobufRectangle2d*>(msg);
|
||||
wpi::PackProtobuf(m->mutable_center(), value.Center());
|
||||
m->set_xwidth(value.XWidth().value());
|
||||
m->set_ywidth(value.YWidth().value());
|
||||
wpi::PackCallback pose{&value.Center()};
|
||||
wpi_proto_ProtobufRectangle2d msg{
|
||||
.center = pose.Callback(),
|
||||
.xWidth = value.XWidth().value(),
|
||||
.yWidth = value.YWidth().value(),
|
||||
};
|
||||
return stream.Encode(msg);
|
||||
}
|
||||
|
||||
@@ -4,25 +4,24 @@
|
||||
|
||||
#include "frc/geometry/proto/Rotation2dProto.h"
|
||||
|
||||
#include <wpi/ProtoHelper.h>
|
||||
#include "wpimath/protobuf/geometry2d.npb.h"
|
||||
|
||||
#include "geometry2d.pb.h"
|
||||
std::optional<frc::Rotation2d> wpi::Protobuf<frc::Rotation2d>::Unpack(
|
||||
InputStream& stream) {
|
||||
wpi_proto_ProtobufRotation2d msg;
|
||||
if (!stream.Decode(msg)) {
|
||||
return {};
|
||||
}
|
||||
|
||||
google::protobuf::Message* wpi::Protobuf<frc::Rotation2d>::New(
|
||||
google::protobuf::Arena* arena) {
|
||||
return wpi::CreateMessage<wpi::proto::ProtobufRotation2d>(arena);
|
||||
}
|
||||
|
||||
frc::Rotation2d wpi::Protobuf<frc::Rotation2d>::Unpack(
|
||||
const google::protobuf::Message& msg) {
|
||||
auto m = static_cast<const wpi::proto::ProtobufRotation2d*>(&msg);
|
||||
return frc::Rotation2d{
|
||||
units::radian_t{m->value()},
|
||||
units::radian_t{msg.value},
|
||||
};
|
||||
}
|
||||
|
||||
void wpi::Protobuf<frc::Rotation2d>::Pack(google::protobuf::Message* msg,
|
||||
bool wpi::Protobuf<frc::Rotation2d>::Pack(OutputStream& stream,
|
||||
const frc::Rotation2d& value) {
|
||||
auto m = static_cast<wpi::proto::ProtobufRotation2d*>(msg);
|
||||
m->set_value(value.Radians().value());
|
||||
wpi_proto_ProtobufRotation2d msg{
|
||||
.value = value.Radians().value(),
|
||||
};
|
||||
return stream.Encode(msg);
|
||||
}
|
||||
|
||||
@@ -4,25 +4,36 @@
|
||||
|
||||
#include "frc/geometry/proto/Rotation3dProto.h"
|
||||
|
||||
#include <wpi/ProtoHelper.h>
|
||||
#include <wpi/protobuf/ProtobufCallbacks.h>
|
||||
|
||||
#include "geometry3d.pb.h"
|
||||
#include "wpimath/protobuf/geometry3d.npb.h"
|
||||
|
||||
google::protobuf::Message* wpi::Protobuf<frc::Rotation3d>::New(
|
||||
google::protobuf::Arena* arena) {
|
||||
return wpi::CreateMessage<wpi::proto::ProtobufRotation3d>(arena);
|
||||
}
|
||||
std::optional<frc::Rotation3d> wpi::Protobuf<frc::Rotation3d>::Unpack(
|
||||
InputStream& stream) {
|
||||
wpi::UnpackCallback<frc::Quaternion> quat;
|
||||
wpi_proto_ProtobufRotation3d msg{
|
||||
.q = quat.Callback(),
|
||||
};
|
||||
if (!stream.Decode(msg)) {
|
||||
return {};
|
||||
}
|
||||
|
||||
auto iquat = quat.Items();
|
||||
|
||||
if (iquat.empty()) {
|
||||
return {};
|
||||
}
|
||||
|
||||
frc::Rotation3d wpi::Protobuf<frc::Rotation3d>::Unpack(
|
||||
const google::protobuf::Message& msg) {
|
||||
auto m = static_cast<const wpi::proto::ProtobufRotation3d*>(&msg);
|
||||
return frc::Rotation3d{
|
||||
wpi::UnpackProtobuf<frc::Quaternion>(m->wpi_q()),
|
||||
iquat[0],
|
||||
};
|
||||
}
|
||||
|
||||
void wpi::Protobuf<frc::Rotation3d>::Pack(google::protobuf::Message* msg,
|
||||
bool wpi::Protobuf<frc::Rotation3d>::Pack(OutputStream& stream,
|
||||
const frc::Rotation3d& value) {
|
||||
auto m = static_cast<wpi::proto::ProtobufRotation3d*>(msg);
|
||||
wpi::PackProtobuf(m->mutable_q(), value.GetQuaternion());
|
||||
wpi::PackCallback quat{&value.GetQuaternion()};
|
||||
wpi_proto_ProtobufRotation3d msg{
|
||||
.q = quat.Callback(),
|
||||
};
|
||||
return stream.Encode(msg);
|
||||
}
|
||||
|
||||
@@ -4,27 +4,42 @@
|
||||
|
||||
#include "frc/geometry/proto/Transform2dProto.h"
|
||||
|
||||
#include <wpi/ProtoHelper.h>
|
||||
#include <wpi/protobuf/ProtobufCallbacks.h>
|
||||
|
||||
#include "geometry2d.pb.h"
|
||||
#include "wpimath/protobuf/geometry2d.npb.h"
|
||||
|
||||
google::protobuf::Message* wpi::Protobuf<frc::Transform2d>::New(
|
||||
google::protobuf::Arena* arena) {
|
||||
return wpi::CreateMessage<wpi::proto::ProtobufTransform2d>(arena);
|
||||
}
|
||||
std::optional<frc::Transform2d> wpi::Protobuf<frc::Transform2d>::Unpack(
|
||||
InputStream& stream) {
|
||||
wpi::UnpackCallback<frc::Translation2d> tsln;
|
||||
wpi::UnpackCallback<frc::Rotation2d> rot;
|
||||
wpi_proto_ProtobufTransform2d msg{
|
||||
.translation = tsln.Callback(),
|
||||
.rotation = rot.Callback(),
|
||||
};
|
||||
if (!stream.Decode(msg)) {
|
||||
return {};
|
||||
}
|
||||
|
||||
auto itsln = tsln.Items();
|
||||
auto irot = rot.Items();
|
||||
|
||||
if (itsln.empty() || irot.empty()) {
|
||||
return {};
|
||||
}
|
||||
|
||||
frc::Transform2d wpi::Protobuf<frc::Transform2d>::Unpack(
|
||||
const google::protobuf::Message& msg) {
|
||||
auto m = static_cast<const wpi::proto::ProtobufTransform2d*>(&msg);
|
||||
return frc::Transform2d{
|
||||
wpi::UnpackProtobuf<frc::Translation2d>(m->wpi_translation()),
|
||||
wpi::UnpackProtobuf<frc::Rotation2d>(m->wpi_rotation()),
|
||||
itsln[0],
|
||||
irot[0],
|
||||
};
|
||||
}
|
||||
|
||||
void wpi::Protobuf<frc::Transform2d>::Pack(google::protobuf::Message* msg,
|
||||
bool wpi::Protobuf<frc::Transform2d>::Pack(OutputStream& stream,
|
||||
const frc::Transform2d& value) {
|
||||
auto m = static_cast<wpi::proto::ProtobufTransform2d*>(msg);
|
||||
wpi::PackProtobuf(m->mutable_translation(), value.Translation());
|
||||
wpi::PackProtobuf(m->mutable_rotation(), value.Rotation());
|
||||
wpi::PackCallback tsln{&value.Translation()};
|
||||
wpi::PackCallback rot{&value.Rotation()};
|
||||
wpi_proto_ProtobufTransform2d msg{
|
||||
.translation = tsln.Callback(),
|
||||
.rotation = rot.Callback(),
|
||||
};
|
||||
return stream.Encode(msg);
|
||||
}
|
||||
|
||||
@@ -4,27 +4,42 @@
|
||||
|
||||
#include "frc/geometry/proto/Transform3dProto.h"
|
||||
|
||||
#include <wpi/ProtoHelper.h>
|
||||
#include <wpi/protobuf/ProtobufCallbacks.h>
|
||||
|
||||
#include "geometry3d.pb.h"
|
||||
#include "wpimath/protobuf/geometry3d.npb.h"
|
||||
|
||||
google::protobuf::Message* wpi::Protobuf<frc::Transform3d>::New(
|
||||
google::protobuf::Arena* arena) {
|
||||
return wpi::CreateMessage<wpi::proto::ProtobufTransform3d>(arena);
|
||||
}
|
||||
std::optional<frc::Transform3d> wpi::Protobuf<frc::Transform3d>::Unpack(
|
||||
InputStream& stream) {
|
||||
wpi::UnpackCallback<frc::Translation3d> tsln;
|
||||
wpi::UnpackCallback<frc::Rotation3d> rot;
|
||||
wpi_proto_ProtobufTransform3d msg{
|
||||
.translation = tsln.Callback(),
|
||||
.rotation = rot.Callback(),
|
||||
};
|
||||
if (!stream.Decode(msg)) {
|
||||
return {};
|
||||
}
|
||||
|
||||
auto itsln = tsln.Items();
|
||||
auto irot = rot.Items();
|
||||
|
||||
if (itsln.empty() || irot.empty()) {
|
||||
return {};
|
||||
}
|
||||
|
||||
frc::Transform3d wpi::Protobuf<frc::Transform3d>::Unpack(
|
||||
const google::protobuf::Message& msg) {
|
||||
auto m = static_cast<const wpi::proto::ProtobufTransform3d*>(&msg);
|
||||
return frc::Transform3d{
|
||||
wpi::UnpackProtobuf<frc::Translation3d>(m->wpi_translation()),
|
||||
wpi::UnpackProtobuf<frc::Rotation3d>(m->wpi_rotation()),
|
||||
itsln[0],
|
||||
irot[0],
|
||||
};
|
||||
}
|
||||
|
||||
void wpi::Protobuf<frc::Transform3d>::Pack(google::protobuf::Message* msg,
|
||||
bool wpi::Protobuf<frc::Transform3d>::Pack(OutputStream& stream,
|
||||
const frc::Transform3d& value) {
|
||||
auto m = static_cast<wpi::proto::ProtobufTransform3d*>(msg);
|
||||
wpi::PackProtobuf(m->mutable_translation(), value.Translation());
|
||||
wpi::PackProtobuf(m->mutable_rotation(), value.Rotation());
|
||||
wpi::PackCallback tsln{&value.Translation()};
|
||||
wpi::PackCallback rot{&value.Rotation()};
|
||||
wpi_proto_ProtobufTransform3d msg{
|
||||
.translation = tsln.Callback(),
|
||||
.rotation = rot.Callback(),
|
||||
};
|
||||
return stream.Encode(msg);
|
||||
}
|
||||
|
||||
@@ -4,27 +4,26 @@
|
||||
|
||||
#include "frc/geometry/proto/Translation2dProto.h"
|
||||
|
||||
#include <wpi/ProtoHelper.h>
|
||||
#include "wpimath/protobuf/geometry2d.npb.h"
|
||||
|
||||
#include "geometry2d.pb.h"
|
||||
std::optional<frc::Translation2d> wpi::Protobuf<frc::Translation2d>::Unpack(
|
||||
InputStream& stream) {
|
||||
wpi_proto_ProtobufTranslation2d msg;
|
||||
if (!stream.Decode(msg)) {
|
||||
return {};
|
||||
}
|
||||
|
||||
google::protobuf::Message* wpi::Protobuf<frc::Translation2d>::New(
|
||||
google::protobuf::Arena* arena) {
|
||||
return wpi::CreateMessage<wpi::proto::ProtobufTranslation2d>(arena);
|
||||
}
|
||||
|
||||
frc::Translation2d wpi::Protobuf<frc::Translation2d>::Unpack(
|
||||
const google::protobuf::Message& msg) {
|
||||
auto m = static_cast<const wpi::proto::ProtobufTranslation2d*>(&msg);
|
||||
return frc::Translation2d{
|
||||
units::meter_t{m->x()},
|
||||
units::meter_t{m->y()},
|
||||
units::meter_t{msg.x},
|
||||
units::meter_t{msg.y},
|
||||
};
|
||||
}
|
||||
|
||||
void wpi::Protobuf<frc::Translation2d>::Pack(google::protobuf::Message* msg,
|
||||
bool wpi::Protobuf<frc::Translation2d>::Pack(OutputStream& stream,
|
||||
const frc::Translation2d& value) {
|
||||
auto m = static_cast<wpi::proto::ProtobufTranslation2d*>(msg);
|
||||
m->set_x(value.X().value());
|
||||
m->set_y(value.Y().value());
|
||||
wpi_proto_ProtobufTranslation2d msg{
|
||||
.x = value.X().value(),
|
||||
.y = value.Y().value(),
|
||||
};
|
||||
return stream.Encode(msg);
|
||||
}
|
||||
|
||||
@@ -4,29 +4,28 @@
|
||||
|
||||
#include "frc/geometry/proto/Translation3dProto.h"
|
||||
|
||||
#include <wpi/ProtoHelper.h>
|
||||
#include "wpimath/protobuf/geometry3d.npb.h"
|
||||
|
||||
#include "geometry3d.pb.h"
|
||||
std::optional<frc::Translation3d> wpi::Protobuf<frc::Translation3d>::Unpack(
|
||||
InputStream& stream) {
|
||||
wpi_proto_ProtobufTranslation3d msg;
|
||||
if (!stream.Decode(msg)) {
|
||||
return {};
|
||||
}
|
||||
|
||||
google::protobuf::Message* wpi::Protobuf<frc::Translation3d>::New(
|
||||
google::protobuf::Arena* arena) {
|
||||
return wpi::CreateMessage<wpi::proto::ProtobufTranslation3d>(arena);
|
||||
}
|
||||
|
||||
frc::Translation3d wpi::Protobuf<frc::Translation3d>::Unpack(
|
||||
const google::protobuf::Message& msg) {
|
||||
auto m = static_cast<const wpi::proto::ProtobufTranslation3d*>(&msg);
|
||||
return frc::Translation3d{
|
||||
units::meter_t{m->x()},
|
||||
units::meter_t{m->y()},
|
||||
units::meter_t{m->z()},
|
||||
units::meter_t{msg.x},
|
||||
units::meter_t{msg.y},
|
||||
units::meter_t{msg.z},
|
||||
};
|
||||
}
|
||||
|
||||
void wpi::Protobuf<frc::Translation3d>::Pack(google::protobuf::Message* msg,
|
||||
bool wpi::Protobuf<frc::Translation3d>::Pack(OutputStream& stream,
|
||||
const frc::Translation3d& value) {
|
||||
auto m = static_cast<wpi::proto::ProtobufTranslation3d*>(msg);
|
||||
m->set_x(value.X().value());
|
||||
m->set_y(value.Y().value());
|
||||
m->set_z(value.Z().value());
|
||||
wpi_proto_ProtobufTranslation3d msg{
|
||||
.x = value.X().value(),
|
||||
.y = value.Y().value(),
|
||||
.z = value.Z().value(),
|
||||
};
|
||||
return stream.Encode(msg);
|
||||
}
|
||||
|
||||
@@ -4,29 +4,28 @@
|
||||
|
||||
#include "frc/geometry/proto/Twist2dProto.h"
|
||||
|
||||
#include <wpi/ProtoHelper.h>
|
||||
#include "wpimath/protobuf/geometry2d.npb.h"
|
||||
|
||||
#include "geometry2d.pb.h"
|
||||
std::optional<frc::Twist2d> wpi::Protobuf<frc::Twist2d>::Unpack(
|
||||
InputStream& stream) {
|
||||
wpi_proto_ProtobufTwist2d msg;
|
||||
if (!stream.Decode(msg)) {
|
||||
return {};
|
||||
}
|
||||
|
||||
google::protobuf::Message* wpi::Protobuf<frc::Twist2d>::New(
|
||||
google::protobuf::Arena* arena) {
|
||||
return wpi::CreateMessage<wpi::proto::ProtobufTwist2d>(arena);
|
||||
}
|
||||
|
||||
frc::Twist2d wpi::Protobuf<frc::Twist2d>::Unpack(
|
||||
const google::protobuf::Message& msg) {
|
||||
auto m = static_cast<const wpi::proto::ProtobufTwist2d*>(&msg);
|
||||
return frc::Twist2d{
|
||||
units::meter_t{m->dx()},
|
||||
units::meter_t{m->dy()},
|
||||
units::radian_t{m->dtheta()},
|
||||
units::meter_t{msg.dx},
|
||||
units::meter_t{msg.dy},
|
||||
units::radian_t{msg.dtheta},
|
||||
};
|
||||
}
|
||||
|
||||
void wpi::Protobuf<frc::Twist2d>::Pack(google::protobuf::Message* msg,
|
||||
bool wpi::Protobuf<frc::Twist2d>::Pack(OutputStream& stream,
|
||||
const frc::Twist2d& value) {
|
||||
auto m = static_cast<wpi::proto::ProtobufTwist2d*>(msg);
|
||||
m->set_dx(value.dx.value());
|
||||
m->set_dy(value.dy.value());
|
||||
m->set_dtheta(value.dtheta.value());
|
||||
wpi_proto_ProtobufTwist2d msg{
|
||||
.dx = value.dx.value(),
|
||||
.dy = value.dy.value(),
|
||||
.dtheta = value.dtheta.value(),
|
||||
};
|
||||
return stream.Encode(msg);
|
||||
}
|
||||
|
||||
@@ -4,32 +4,30 @@
|
||||
|
||||
#include "frc/geometry/proto/Twist3dProto.h"
|
||||
|
||||
#include <wpi/ProtoHelper.h>
|
||||
#include "wpimath/protobuf/geometry3d.npb.h"
|
||||
|
||||
#include "geometry3d.pb.h"
|
||||
std::optional<frc::Twist3d> wpi::Protobuf<frc::Twist3d>::Unpack(
|
||||
InputStream& stream) {
|
||||
wpi_proto_ProtobufTwist3d msg;
|
||||
if (!stream.Decode(msg)) {
|
||||
return {};
|
||||
}
|
||||
|
||||
google::protobuf::Message* wpi::Protobuf<frc::Twist3d>::New(
|
||||
google::protobuf::Arena* arena) {
|
||||
return wpi::CreateMessage<wpi::proto::ProtobufTwist3d>(arena);
|
||||
}
|
||||
|
||||
frc::Twist3d wpi::Protobuf<frc::Twist3d>::Unpack(
|
||||
const google::protobuf::Message& msg) {
|
||||
auto m = static_cast<const wpi::proto::ProtobufTwist3d*>(&msg);
|
||||
return frc::Twist3d{
|
||||
units::meter_t{m->dx()}, units::meter_t{m->dy()},
|
||||
units::meter_t{m->dz()}, units::radian_t{m->rx()},
|
||||
units::radian_t{m->ry()}, units::radian_t{m->rz()},
|
||||
units::meter_t{msg.dx}, units::meter_t{msg.dy}, units::meter_t{msg.dz},
|
||||
units::radian_t{msg.rx}, units::radian_t{msg.ry}, units::radian_t{msg.rz},
|
||||
};
|
||||
}
|
||||
|
||||
void wpi::Protobuf<frc::Twist3d>::Pack(google::protobuf::Message* msg,
|
||||
bool wpi::Protobuf<frc::Twist3d>::Pack(OutputStream& stream,
|
||||
const frc::Twist3d& value) {
|
||||
auto m = static_cast<wpi::proto::ProtobufTwist3d*>(msg);
|
||||
m->set_dx(value.dx.value());
|
||||
m->set_dy(value.dy.value());
|
||||
m->set_dz(value.dz.value());
|
||||
m->set_rx(value.rx.value());
|
||||
m->set_ry(value.ry.value());
|
||||
m->set_rz(value.rz.value());
|
||||
wpi_proto_ProtobufTwist3d msg{
|
||||
.dx = value.dx.value(),
|
||||
.dy = value.dy.value(),
|
||||
.dz = value.dz.value(),
|
||||
.rx = value.rx.value(),
|
||||
.ry = value.ry.value(),
|
||||
.rz = value.rz.value(),
|
||||
};
|
||||
return stream.Encode(msg);
|
||||
}
|
||||
|
||||
@@ -4,29 +4,28 @@
|
||||
|
||||
#include "frc/kinematics/proto/ChassisSpeedsProto.h"
|
||||
|
||||
#include <wpi/ProtoHelper.h>
|
||||
#include "wpimath/protobuf/kinematics.npb.h"
|
||||
|
||||
#include "kinematics.pb.h"
|
||||
std::optional<frc::ChassisSpeeds> wpi::Protobuf<frc::ChassisSpeeds>::Unpack(
|
||||
InputStream& stream) {
|
||||
wpi_proto_ProtobufChassisSpeeds msg;
|
||||
if (!stream.Decode(msg)) {
|
||||
return {};
|
||||
}
|
||||
|
||||
google::protobuf::Message* wpi::Protobuf<frc::ChassisSpeeds>::New(
|
||||
google::protobuf::Arena* arena) {
|
||||
return wpi::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()},
|
||||
units::meters_per_second_t{msg.vx},
|
||||
units::meters_per_second_t{msg.vy},
|
||||
units::radians_per_second_t{msg.omega},
|
||||
};
|
||||
}
|
||||
|
||||
void wpi::Protobuf<frc::ChassisSpeeds>::Pack(google::protobuf::Message* msg,
|
||||
bool wpi::Protobuf<frc::ChassisSpeeds>::Pack(OutputStream& stream,
|
||||
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());
|
||||
wpi_proto_ProtobufChassisSpeeds msg{
|
||||
.vx = value.vx.value(),
|
||||
.vy = value.vy.value(),
|
||||
.omega = value.omega.value(),
|
||||
};
|
||||
return stream.Encode(msg);
|
||||
}
|
||||
|
||||
@@ -4,29 +4,24 @@
|
||||
|
||||
#include "frc/kinematics/proto/DifferentialDriveKinematicsProto.h"
|
||||
|
||||
#include <wpi/ProtoHelper.h>
|
||||
#include "wpimath/protobuf/kinematics.npb.h"
|
||||
|
||||
#include "kinematics.pb.h"
|
||||
std::optional<frc::DifferentialDriveKinematics>
|
||||
wpi::Protobuf<frc::DifferentialDriveKinematics>::Unpack(InputStream& stream) {
|
||||
wpi_proto_ProtobufDifferentialDriveKinematics msg;
|
||||
if (!stream.Decode(msg)) {
|
||||
return {};
|
||||
}
|
||||
|
||||
google::protobuf::Message* wpi::Protobuf<frc::DifferentialDriveKinematics>::New(
|
||||
google::protobuf::Arena* arena) {
|
||||
return wpi::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()},
|
||||
units::meter_t{msg.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());
|
||||
bool wpi::Protobuf<frc::DifferentialDriveKinematics>::Pack(
|
||||
OutputStream& stream, const frc::DifferentialDriveKinematics& value) {
|
||||
wpi_proto_ProtobufDifferentialDriveKinematics msg{
|
||||
.track_width = value.trackWidth.value(),
|
||||
};
|
||||
return stream.Encode(msg);
|
||||
}
|
||||
|
||||
@@ -4,33 +4,26 @@
|
||||
|
||||
#include "frc/kinematics/proto/DifferentialDriveWheelPositionsProto.h"
|
||||
|
||||
#include <wpi/ProtoHelper.h>
|
||||
#include "wpimath/protobuf/kinematics.npb.h"
|
||||
|
||||
#include "kinematics.pb.h"
|
||||
std::optional<frc::DifferentialDriveWheelPositions> wpi::Protobuf<
|
||||
frc::DifferentialDriveWheelPositions>::Unpack(InputStream& stream) {
|
||||
wpi_proto_ProtobufDifferentialDriveWheelPositions msg;
|
||||
if (!stream.Decode(msg)) {
|
||||
return {};
|
||||
}
|
||||
|
||||
google::protobuf::Message* wpi::Protobuf<
|
||||
frc::DifferentialDriveWheelPositions>::New(google::protobuf::Arena* arena) {
|
||||
return wpi::CreateMessage<
|
||||
wpi::proto::ProtobufDifferentialDriveWheelPositions>(arena);
|
||||
}
|
||||
|
||||
frc::DifferentialDriveWheelPositions
|
||||
wpi::Protobuf<frc::DifferentialDriveWheelPositions>::Unpack(
|
||||
const google::protobuf::Message& msg) {
|
||||
auto m =
|
||||
static_cast<const wpi::proto::ProtobufDifferentialDriveWheelPositions*>(
|
||||
&msg);
|
||||
return frc::DifferentialDriveWheelPositions{
|
||||
units::meter_t{m->left()},
|
||||
units::meter_t{m->right()},
|
||||
units::meter_t{msg.left},
|
||||
units::meter_t{msg.right},
|
||||
};
|
||||
}
|
||||
|
||||
void wpi::Protobuf<frc::DifferentialDriveWheelPositions>::Pack(
|
||||
google::protobuf::Message* msg,
|
||||
const frc::DifferentialDriveWheelPositions& value) {
|
||||
auto m =
|
||||
static_cast<wpi::proto::ProtobufDifferentialDriveWheelPositions*>(msg);
|
||||
m->set_left(value.left.value());
|
||||
m->set_right(value.right.value());
|
||||
bool wpi::Protobuf<frc::DifferentialDriveWheelPositions>::Pack(
|
||||
OutputStream& stream, const frc::DifferentialDriveWheelPositions& value) {
|
||||
wpi_proto_ProtobufDifferentialDriveWheelPositions msg{
|
||||
.left = value.left.value(),
|
||||
.right = value.right.value(),
|
||||
};
|
||||
return stream.Encode(msg);
|
||||
}
|
||||
|
||||
@@ -4,31 +4,26 @@
|
||||
|
||||
#include "frc/kinematics/proto/DifferentialDriveWheelSpeedsProto.h"
|
||||
|
||||
#include <wpi/ProtoHelper.h>
|
||||
#include "wpimath/protobuf/kinematics.npb.h"
|
||||
|
||||
#include "kinematics.pb.h"
|
||||
std::optional<frc::DifferentialDriveWheelSpeeds>
|
||||
wpi::Protobuf<frc::DifferentialDriveWheelSpeeds>::Unpack(InputStream& stream) {
|
||||
wpi_proto_ProtobufDifferentialDriveWheelSpeeds msg;
|
||||
if (!stream.Decode(msg)) {
|
||||
return {};
|
||||
}
|
||||
|
||||
google::protobuf::Message* wpi::Protobuf<
|
||||
frc::DifferentialDriveWheelSpeeds>::New(google::protobuf::Arena* arena) {
|
||||
return wpi::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()},
|
||||
units::meters_per_second_t{msg.left},
|
||||
units::meters_per_second_t{msg.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());
|
||||
bool wpi::Protobuf<frc::DifferentialDriveWheelSpeeds>::Pack(
|
||||
OutputStream& stream, const frc::DifferentialDriveWheelSpeeds& value) {
|
||||
wpi_proto_ProtobufDifferentialDriveWheelSpeeds msg{
|
||||
.left = value.left.value(),
|
||||
.right = value.right.value(),
|
||||
};
|
||||
return stream.Encode(msg);
|
||||
}
|
||||
|
||||
@@ -4,31 +4,55 @@
|
||||
|
||||
#include "frc/kinematics/proto/MecanumDriveKinematicsProto.h"
|
||||
|
||||
#include <wpi/ProtoHelper.h>
|
||||
#include <wpi/protobuf/ProtobufCallbacks.h>
|
||||
|
||||
#include "kinematics.pb.h"
|
||||
#include "wpimath/protobuf/kinematics.npb.h"
|
||||
|
||||
google::protobuf::Message* wpi::Protobuf<frc::MecanumDriveKinematics>::New(
|
||||
google::protobuf::Arena* arena) {
|
||||
return wpi::CreateMessage<wpi::proto::ProtobufMecanumDriveKinematics>(arena);
|
||||
}
|
||||
std::optional<frc::MecanumDriveKinematics>
|
||||
wpi::Protobuf<frc::MecanumDriveKinematics>::Unpack(InputStream& stream) {
|
||||
wpi::UnpackCallback<frc::Translation2d> frontLeft;
|
||||
wpi::UnpackCallback<frc::Translation2d> frontRight;
|
||||
wpi::UnpackCallback<frc::Translation2d> rearLeft;
|
||||
wpi::UnpackCallback<frc::Translation2d> rearRight;
|
||||
wpi_proto_ProtobufMecanumDriveKinematics msg{
|
||||
.front_left = frontLeft.Callback(),
|
||||
.front_right = frontRight.Callback(),
|
||||
.rear_left = rearLeft.Callback(),
|
||||
.rear_right = rearRight.Callback(),
|
||||
};
|
||||
if (!stream.Decode(msg)) {
|
||||
return {};
|
||||
}
|
||||
|
||||
auto ifrontLeft = frontLeft.Items();
|
||||
auto ifrontRight = frontRight.Items();
|
||||
auto irearLeft = rearLeft.Items();
|
||||
auto irearRight = rearRight.Items();
|
||||
|
||||
if (ifrontLeft.empty() || ifrontRight.empty() || irearLeft.empty() ||
|
||||
irearRight.empty()) {
|
||||
return {};
|
||||
}
|
||||
|
||||
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->wpi_front_left()),
|
||||
wpi::UnpackProtobuf<frc::Translation2d>(m->wpi_front_right()),
|
||||
wpi::UnpackProtobuf<frc::Translation2d>(m->wpi_rear_left()),
|
||||
wpi::UnpackProtobuf<frc::Translation2d>(m->wpi_rear_right()),
|
||||
ifrontLeft[0],
|
||||
ifrontRight[0],
|
||||
irearLeft[0],
|
||||
irearRight[0],
|
||||
};
|
||||
}
|
||||
|
||||
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.GetFrontLeft());
|
||||
wpi::PackProtobuf(m->mutable_front_right(), value.GetFrontRight());
|
||||
wpi::PackProtobuf(m->mutable_rear_left(), value.GetRearLeft());
|
||||
wpi::PackProtobuf(m->mutable_rear_right(), value.GetRearRight());
|
||||
bool wpi::Protobuf<frc::MecanumDriveKinematics>::Pack(
|
||||
OutputStream& stream, const frc::MecanumDriveKinematics& value) {
|
||||
wpi::PackCallback frontLeft{&value.GetFrontLeft()};
|
||||
wpi::PackCallback frontRight{&value.GetFrontRight()};
|
||||
wpi::PackCallback rearLeft{&value.GetRearLeft()};
|
||||
wpi::PackCallback rearRight{&value.GetRearRight()};
|
||||
wpi_proto_ProtobufMecanumDriveKinematics msg{
|
||||
.front_left = frontLeft.Callback(),
|
||||
.front_right = frontRight.Callback(),
|
||||
.rear_left = rearLeft.Callback(),
|
||||
.rear_right = rearRight.Callback(),
|
||||
};
|
||||
return stream.Encode(msg);
|
||||
}
|
||||
|
||||
@@ -4,35 +4,30 @@
|
||||
|
||||
#include "frc/kinematics/proto/MecanumDriveWheelPositionsProto.h"
|
||||
|
||||
#include <wpi/ProtoHelper.h>
|
||||
#include "wpimath/protobuf/kinematics.npb.h"
|
||||
|
||||
#include "kinematics.pb.h"
|
||||
std::optional<frc::MecanumDriveWheelPositions>
|
||||
wpi::Protobuf<frc::MecanumDriveWheelPositions>::Unpack(InputStream& stream) {
|
||||
wpi_proto_ProtobufMecanumDriveWheelPositions msg;
|
||||
if (!stream.Decode(msg)) {
|
||||
return {};
|
||||
}
|
||||
|
||||
google::protobuf::Message* wpi::Protobuf<frc::MecanumDriveWheelPositions>::New(
|
||||
google::protobuf::Arena* arena) {
|
||||
return wpi::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()},
|
||||
units::meter_t{msg.front_left},
|
||||
units::meter_t{msg.front_right},
|
||||
units::meter_t{msg.rear_left},
|
||||
units::meter_t{msg.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());
|
||||
bool wpi::Protobuf<frc::MecanumDriveWheelPositions>::Pack(
|
||||
OutputStream& stream, const frc::MecanumDriveWheelPositions& value) {
|
||||
wpi_proto_ProtobufMecanumDriveWheelPositions msg{
|
||||
.front_left = value.frontLeft.value(),
|
||||
.front_right = value.frontRight.value(),
|
||||
.rear_left = value.rearLeft.value(),
|
||||
.rear_right = value.rearRight.value(),
|
||||
};
|
||||
return stream.Encode(msg);
|
||||
}
|
||||
|
||||
@@ -4,33 +4,30 @@
|
||||
|
||||
#include "frc/kinematics/proto/MecanumDriveWheelSpeedsProto.h"
|
||||
|
||||
#include <wpi/ProtoHelper.h>
|
||||
#include "wpimath/protobuf/kinematics.npb.h"
|
||||
|
||||
#include "kinematics.pb.h"
|
||||
std::optional<frc::MecanumDriveWheelSpeeds>
|
||||
wpi::Protobuf<frc::MecanumDriveWheelSpeeds>::Unpack(InputStream& stream) {
|
||||
wpi_proto_ProtobufMecanumDriveWheelSpeeds msg;
|
||||
if (!stream.Decode(msg)) {
|
||||
return {};
|
||||
}
|
||||
|
||||
google::protobuf::Message* wpi::Protobuf<frc::MecanumDriveWheelSpeeds>::New(
|
||||
google::protobuf::Arena* arena) {
|
||||
return wpi::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()},
|
||||
units::meters_per_second_t{msg.front_left},
|
||||
units::meters_per_second_t{msg.front_right},
|
||||
units::meters_per_second_t{msg.rear_left},
|
||||
units::meters_per_second_t{msg.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());
|
||||
bool wpi::Protobuf<frc::MecanumDriveWheelSpeeds>::Pack(
|
||||
OutputStream& stream, const frc::MecanumDriveWheelSpeeds& value) {
|
||||
wpi_proto_ProtobufMecanumDriveWheelSpeeds msg{
|
||||
.front_left = value.frontLeft.value(),
|
||||
.front_right = value.frontRight.value(),
|
||||
.rear_left = value.rearLeft.value(),
|
||||
.rear_right = value.rearRight.value(),
|
||||
};
|
||||
return stream.Encode(msg);
|
||||
}
|
||||
|
||||
@@ -4,27 +4,39 @@
|
||||
|
||||
#include "frc/kinematics/proto/SwerveModulePositionProto.h"
|
||||
|
||||
#include <wpi/ProtoHelper.h>
|
||||
#include <wpi/protobuf/ProtobufCallbacks.h>
|
||||
|
||||
#include "kinematics.pb.h"
|
||||
#include "wpimath/protobuf/kinematics.npb.h"
|
||||
|
||||
google::protobuf::Message* wpi::Protobuf<frc::SwerveModulePosition>::New(
|
||||
google::protobuf::Arena* arena) {
|
||||
return wpi::CreateMessage<wpi::proto::ProtobufSwerveModulePosition>(arena);
|
||||
}
|
||||
std::optional<frc::SwerveModulePosition>
|
||||
wpi::Protobuf<frc::SwerveModulePosition>::Unpack(InputStream& stream) {
|
||||
wpi::UnpackCallback<frc::Rotation2d> angle;
|
||||
wpi_proto_ProtobufSwerveModulePosition msg{
|
||||
.distance = 0,
|
||||
.angle = angle.Callback(),
|
||||
};
|
||||
if (!stream.Decode(msg)) {
|
||||
return {};
|
||||
}
|
||||
|
||||
auto iangle = angle.Items();
|
||||
|
||||
if (iangle.empty()) {
|
||||
return {};
|
||||
}
|
||||
|
||||
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->wpi_angle()),
|
||||
units::meter_t{msg.distance},
|
||||
iangle[0],
|
||||
};
|
||||
}
|
||||
|
||||
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);
|
||||
bool wpi::Protobuf<frc::SwerveModulePosition>::Pack(
|
||||
OutputStream& stream, const frc::SwerveModulePosition& value) {
|
||||
wpi::PackCallback angle{&value.angle};
|
||||
wpi_proto_ProtobufSwerveModulePosition msg{
|
||||
.distance = value.distance.value(),
|
||||
.angle = angle.Callback(),
|
||||
};
|
||||
return stream.Encode(msg);
|
||||
}
|
||||
|
||||
@@ -4,27 +4,39 @@
|
||||
|
||||
#include "frc/kinematics/proto/SwerveModuleStateProto.h"
|
||||
|
||||
#include <wpi/ProtoHelper.h>
|
||||
#include <wpi/protobuf/ProtobufCallbacks.h>
|
||||
|
||||
#include "kinematics.pb.h"
|
||||
#include "wpimath/protobuf/kinematics.npb.h"
|
||||
|
||||
google::protobuf::Message* wpi::Protobuf<frc::SwerveModuleState>::New(
|
||||
google::protobuf::Arena* arena) {
|
||||
return wpi::CreateMessage<wpi::proto::ProtobufSwerveModuleState>(arena);
|
||||
}
|
||||
std::optional<frc::SwerveModuleState>
|
||||
wpi::Protobuf<frc::SwerveModuleState>::Unpack(InputStream& stream) {
|
||||
wpi::UnpackCallback<frc::Rotation2d> angle;
|
||||
wpi_proto_ProtobufSwerveModuleState msg{
|
||||
.speed = 0,
|
||||
.angle = angle.Callback(),
|
||||
};
|
||||
if (!stream.Decode(msg)) {
|
||||
return {};
|
||||
}
|
||||
|
||||
auto iangle = angle.Items();
|
||||
|
||||
if (iangle.empty()) {
|
||||
return {};
|
||||
}
|
||||
|
||||
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->wpi_angle()),
|
||||
units::meters_per_second_t{msg.speed},
|
||||
iangle[0],
|
||||
};
|
||||
}
|
||||
|
||||
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);
|
||||
bool wpi::Protobuf<frc::SwerveModuleState>::Pack(
|
||||
OutputStream& stream, const frc::SwerveModuleState& value) {
|
||||
wpi::PackCallback angle{&value.angle};
|
||||
wpi_proto_ProtobufSwerveModuleState msg{
|
||||
.speed = value.speed.value(),
|
||||
.angle = angle.Callback(),
|
||||
};
|
||||
return stream.Encode(msg);
|
||||
}
|
||||
|
||||
@@ -4,32 +4,50 @@
|
||||
|
||||
#include "frc/spline/proto/CubicHermiteSplineProto.h"
|
||||
|
||||
#include <wpi/ProtoHelper.h>
|
||||
#include <wpi/protobuf/ProtobufCallbacks.h>
|
||||
|
||||
#include "spline.pb.h"
|
||||
#include "wpimath/protobuf/spline.npb.h"
|
||||
|
||||
google::protobuf::Message* wpi::Protobuf<frc::CubicHermiteSpline>::New(
|
||||
google::protobuf::Arena* arena) {
|
||||
return wpi::CreateMessage<wpi::proto::ProtobufCubicHermiteSpline>(arena);
|
||||
}
|
||||
std::optional<frc::CubicHermiteSpline>
|
||||
wpi::Protobuf<frc::CubicHermiteSpline>::Unpack(InputStream& stream) {
|
||||
wpi::WpiArrayUnpackCallback<double, 2> xInitial;
|
||||
wpi::WpiArrayUnpackCallback<double, 2> xFinal;
|
||||
wpi::WpiArrayUnpackCallback<double, 2> yInitial;
|
||||
wpi::WpiArrayUnpackCallback<double, 2> yFinal;
|
||||
wpi_proto_ProtobufCubicHermiteSpline msg{
|
||||
.x_initial = xInitial.Callback(),
|
||||
.x_final = xFinal.Callback(),
|
||||
.y_initial = yInitial.Callback(),
|
||||
.y_final = yFinal.Callback(),
|
||||
};
|
||||
if (!stream.Decode(msg)) {
|
||||
return {};
|
||||
}
|
||||
|
||||
if (!xInitial.IsFull() || !yInitial.IsFull() || !xFinal.IsFull() ||
|
||||
!yFinal.IsFull()) {
|
||||
return {};
|
||||
}
|
||||
|
||||
frc::CubicHermiteSpline wpi::Protobuf<frc::CubicHermiteSpline>::Unpack(
|
||||
const google::protobuf::Message& msg) {
|
||||
auto m = static_cast<const wpi::proto::ProtobufCubicHermiteSpline*>(&msg);
|
||||
return frc::CubicHermiteSpline{
|
||||
wpi::UnpackProtobufArray<double, 2>(m->x_initial()),
|
||||
wpi::UnpackProtobufArray<double, 2>(m->x_final()),
|
||||
wpi::UnpackProtobufArray<double, 2>(m->y_initial()),
|
||||
wpi::UnpackProtobufArray<double, 2>(m->y_final())};
|
||||
xInitial.Array(),
|
||||
xFinal.Array(),
|
||||
yInitial.Array(),
|
||||
yFinal.Array(),
|
||||
};
|
||||
}
|
||||
|
||||
void wpi::Protobuf<frc::CubicHermiteSpline>::Pack(
|
||||
google::protobuf::Message* msg, const frc::CubicHermiteSpline& value) {
|
||||
auto m = static_cast<wpi::proto::ProtobufCubicHermiteSpline*>(msg);
|
||||
wpi::PackProtobufArray(m->mutable_x_initial(),
|
||||
value.GetInitialControlVector().x);
|
||||
wpi::PackProtobufArray(m->mutable_x_final(), value.GetFinalControlVector().x);
|
||||
wpi::PackProtobufArray(m->mutable_y_initial(),
|
||||
value.GetInitialControlVector().y);
|
||||
wpi::PackProtobufArray(m->mutable_y_final(), value.GetFinalControlVector().y);
|
||||
bool wpi::Protobuf<frc::CubicHermiteSpline>::Pack(
|
||||
OutputStream& stream, const frc::CubicHermiteSpline& value) {
|
||||
wpi::PackCallback<double> xInitial{value.GetInitialControlVector().x};
|
||||
wpi::PackCallback<double> xFinal{value.GetFinalControlVector().x};
|
||||
wpi::PackCallback<double> yInitial{value.GetInitialControlVector().y};
|
||||
wpi::PackCallback<double> yFinal{value.GetFinalControlVector().y};
|
||||
wpi_proto_ProtobufCubicHermiteSpline msg{
|
||||
.x_initial = xInitial.Callback(),
|
||||
.x_final = xFinal.Callback(),
|
||||
.y_initial = yInitial.Callback(),
|
||||
.y_final = yFinal.Callback(),
|
||||
};
|
||||
return stream.Encode(msg);
|
||||
}
|
||||
|
||||
@@ -4,32 +4,50 @@
|
||||
|
||||
#include "frc/spline/proto/QuinticHermiteSplineProto.h"
|
||||
|
||||
#include <wpi/ProtoHelper.h>
|
||||
#include <wpi/protobuf/ProtobufCallbacks.h>
|
||||
|
||||
#include "spline.pb.h"
|
||||
#include "wpimath/protobuf/spline.npb.h"
|
||||
|
||||
google::protobuf::Message* wpi::Protobuf<frc::QuinticHermiteSpline>::New(
|
||||
google::protobuf::Arena* arena) {
|
||||
return wpi::CreateMessage<wpi::proto::ProtobufQuinticHermiteSpline>(arena);
|
||||
}
|
||||
std::optional<frc::QuinticHermiteSpline>
|
||||
wpi::Protobuf<frc::QuinticHermiteSpline>::Unpack(InputStream& stream) {
|
||||
wpi::WpiArrayUnpackCallback<double, 3> xInitial;
|
||||
wpi::WpiArrayUnpackCallback<double, 3> xFinal;
|
||||
wpi::WpiArrayUnpackCallback<double, 3> yInitial;
|
||||
wpi::WpiArrayUnpackCallback<double, 3> yFinal;
|
||||
wpi_proto_ProtobufQuinticHermiteSpline msg{
|
||||
.x_initial = xInitial.Callback(),
|
||||
.x_final = xFinal.Callback(),
|
||||
.y_initial = yInitial.Callback(),
|
||||
.y_final = yFinal.Callback(),
|
||||
};
|
||||
if (!stream.Decode(msg)) {
|
||||
return {};
|
||||
}
|
||||
|
||||
if (!xInitial.IsFull() || !yInitial.IsFull() || !xFinal.IsFull() ||
|
||||
!yFinal.IsFull()) {
|
||||
return {};
|
||||
}
|
||||
|
||||
frc::QuinticHermiteSpline wpi::Protobuf<frc::QuinticHermiteSpline>::Unpack(
|
||||
const google::protobuf::Message& msg) {
|
||||
auto m = static_cast<const wpi::proto::ProtobufQuinticHermiteSpline*>(&msg);
|
||||
return frc::QuinticHermiteSpline{
|
||||
wpi::UnpackProtobufArray<double, 3>(m->x_initial()),
|
||||
wpi::UnpackProtobufArray<double, 3>(m->x_final()),
|
||||
wpi::UnpackProtobufArray<double, 3>(m->y_initial()),
|
||||
wpi::UnpackProtobufArray<double, 3>(m->y_final())};
|
||||
xInitial.Array(),
|
||||
xFinal.Array(),
|
||||
yInitial.Array(),
|
||||
yFinal.Array(),
|
||||
};
|
||||
}
|
||||
|
||||
void wpi::Protobuf<frc::QuinticHermiteSpline>::Pack(
|
||||
google::protobuf::Message* msg, const frc::QuinticHermiteSpline& value) {
|
||||
auto m = static_cast<wpi::proto::ProtobufQuinticHermiteSpline*>(msg);
|
||||
wpi::PackProtobufArray(m->mutable_x_initial(),
|
||||
value.GetInitialControlVector().x);
|
||||
wpi::PackProtobufArray(m->mutable_x_final(), value.GetFinalControlVector().x);
|
||||
wpi::PackProtobufArray(m->mutable_y_initial(),
|
||||
value.GetInitialControlVector().y);
|
||||
wpi::PackProtobufArray(m->mutable_y_final(), value.GetFinalControlVector().y);
|
||||
bool wpi::Protobuf<frc::QuinticHermiteSpline>::Pack(
|
||||
OutputStream& stream, const frc::QuinticHermiteSpline& value) {
|
||||
wpi::PackCallback<double> xInitial{value.GetInitialControlVector().x};
|
||||
wpi::PackCallback<double> xFinal{value.GetFinalControlVector().x};
|
||||
wpi::PackCallback<double> yInitial{value.GetInitialControlVector().y};
|
||||
wpi::PackCallback<double> yFinal{value.GetFinalControlVector().y};
|
||||
wpi_proto_ProtobufQuinticHermiteSpline msg{
|
||||
.x_initial = xInitial.Callback(),
|
||||
.x_final = xFinal.Callback(),
|
||||
.y_initial = yInitial.Callback(),
|
||||
.y_final = yFinal.Callback(),
|
||||
};
|
||||
return stream.Encode(msg);
|
||||
}
|
||||
|
||||
@@ -4,33 +4,34 @@
|
||||
|
||||
#include "frc/system/plant/proto/DCMotorProto.h"
|
||||
|
||||
#include <wpi/ProtoHelper.h>
|
||||
#include <optional>
|
||||
|
||||
#include "plant.pb.h"
|
||||
#include "wpimath/protobuf/plant.npb.h"
|
||||
|
||||
google::protobuf::Message* wpi::Protobuf<frc::DCMotor>::New(
|
||||
google::protobuf::Arena* arena) {
|
||||
return wpi::CreateMessage<wpi::proto::ProtobufDCMotor>(arena);
|
||||
}
|
||||
std::optional<frc::DCMotor> wpi::Protobuf<frc::DCMotor>::Unpack(
|
||||
InputStream& stream) {
|
||||
wpi_proto_ProtobufDCMotor msg;
|
||||
if (!stream.Decode(msg)) {
|
||||
return {};
|
||||
}
|
||||
|
||||
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()},
|
||||
units::volt_t{msg.nominal_voltage},
|
||||
units::newton_meter_t{msg.stall_torque},
|
||||
units::ampere_t{msg.stall_current},
|
||||
units::ampere_t{msg.free_current},
|
||||
units::radians_per_second_t{msg.free_speed},
|
||||
};
|
||||
}
|
||||
|
||||
void wpi::Protobuf<frc::DCMotor>::Pack(google::protobuf::Message* msg,
|
||||
bool wpi::Protobuf<frc::DCMotor>::Pack(OutputStream& stream,
|
||||
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());
|
||||
wpi_proto_ProtobufDCMotor msg{
|
||||
.nominal_voltage = value.nominalVoltage.value(),
|
||||
.stall_torque = value.stallTorque.value(),
|
||||
.stall_current = value.stallCurrent.value(),
|
||||
.free_current = value.freeCurrent.value(),
|
||||
.free_speed = value.freeSpeed.value(),
|
||||
};
|
||||
return stream.Encode(msg);
|
||||
}
|
||||
|
||||
@@ -6,31 +6,28 @@
|
||||
|
||||
#include <vector>
|
||||
|
||||
#include <wpi/ProtoHelper.h>
|
||||
#include <wpi/protobuf/ProtobufCallbacks.h>
|
||||
|
||||
#include "trajectory.pb.h"
|
||||
#include "wpimath/protobuf/trajectory.npb.h"
|
||||
|
||||
google::protobuf::Message* wpi::Protobuf<frc::Trajectory>::New(
|
||||
google::protobuf::Arena* arena) {
|
||||
return wpi::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));
|
||||
std::optional<frc::Trajectory> wpi::Protobuf<frc::Trajectory>::Unpack(
|
||||
InputStream& stream) {
|
||||
wpi::StdVectorUnpackCallback<frc::Trajectory::State, SIZE_MAX> states;
|
||||
wpi_proto_ProtobufTrajectory msg{
|
||||
.states = states.Callback(),
|
||||
};
|
||||
if (!stream.Decode(msg)) {
|
||||
return {};
|
||||
}
|
||||
return frc::Trajectory{states};
|
||||
|
||||
return frc::Trajectory{states.Vec()};
|
||||
}
|
||||
|
||||
void wpi::Protobuf<frc::Trajectory>::Pack(google::protobuf::Message* msg,
|
||||
bool wpi::Protobuf<frc::Trajectory>::Pack(OutputStream& stream,
|
||||
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);
|
||||
}
|
||||
wpi::PackCallback<frc::Trajectory::State> states{value.States()};
|
||||
wpi_proto_ProtobufTrajectory msg{
|
||||
.states = states.Callback(),
|
||||
};
|
||||
return stream.Encode(msg);
|
||||
}
|
||||
|
||||
@@ -4,33 +4,46 @@
|
||||
|
||||
#include "frc/trajectory/proto/TrajectoryStateProto.h"
|
||||
|
||||
#include <wpi/ProtoHelper.h>
|
||||
#include <utility>
|
||||
|
||||
#include "trajectory.pb.h"
|
||||
#include <wpi/protobuf/ProtobufCallbacks.h>
|
||||
|
||||
google::protobuf::Message* wpi::Protobuf<frc::Trajectory::State>::New(
|
||||
google::protobuf::Arena* arena) {
|
||||
return wpi::CreateMessage<wpi::proto::ProtobufTrajectoryState>(arena);
|
||||
}
|
||||
#include "wpimath/protobuf/trajectory.npb.h"
|
||||
|
||||
std::optional<frc::Trajectory::State>
|
||||
wpi::Protobuf<frc::Trajectory::State>::Unpack(InputStream& stream) {
|
||||
wpi::UnpackCallback<frc::Pose2d> pose;
|
||||
wpi_proto_ProtobufTrajectoryState msg;
|
||||
msg.pose = pose.Callback();
|
||||
|
||||
if (!stream.Decode(msg)) {
|
||||
return {};
|
||||
}
|
||||
|
||||
auto ipose = pose.Items();
|
||||
|
||||
if (ipose.empty()) {
|
||||
return {};
|
||||
}
|
||||
|
||||
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->wpi_pose()),
|
||||
units::curvature_t{m->curvature()},
|
||||
units::second_t{msg.time},
|
||||
units::meters_per_second_t{msg.velocity},
|
||||
units::meters_per_second_squared_t{msg.acceleration},
|
||||
std::move(ipose[0]),
|
||||
units::curvature_t{msg.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());
|
||||
bool wpi::Protobuf<frc::Trajectory::State>::Pack(
|
||||
OutputStream& stream, const frc::Trajectory::State& value) {
|
||||
wpi::PackCallback pose{&value.pose};
|
||||
wpi_proto_ProtobufTrajectoryState msg{
|
||||
.time = value.t.value(),
|
||||
.velocity = value.velocity.value(),
|
||||
.acceleration = value.acceleration.value(),
|
||||
.pose = pose.Callback(),
|
||||
.curvature = value.curvature.value(),
|
||||
};
|
||||
return stream.Encode(msg);
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user