mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +00:00
[wpimath] Add structured data support for DifferentialDriveWheelPositions (#6412)
This commit is contained in:
@@ -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/kinematics/proto/DifferentialDriveWheelPositionsProto.h"
|
||||
|
||||
#include "kinematics.pb.h"
|
||||
|
||||
google::protobuf::Message* wpi::Protobuf<
|
||||
frc::DifferentialDriveWheelPositions>::New(google::protobuf::Arena* arena) {
|
||||
return google::protobuf::Arena::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()},
|
||||
};
|
||||
}
|
||||
|
||||
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());
|
||||
}
|
||||
@@ -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/DifferentialDriveWheelPositionsStruct.h"
|
||||
|
||||
namespace {
|
||||
constexpr size_t kLeftOff = 0;
|
||||
constexpr size_t kRightOff = kLeftOff + 8;
|
||||
} // namespace
|
||||
|
||||
using StructType = wpi::Struct<frc::DifferentialDriveWheelPositions>;
|
||||
|
||||
frc::DifferentialDriveWheelPositions StructType::Unpack(
|
||||
std::span<const uint8_t> data) {
|
||||
return frc::DifferentialDriveWheelPositions{
|
||||
units::meter_t{wpi::UnpackStruct<double, kLeftOff>(data)},
|
||||
units::meter_t{wpi::UnpackStruct<double, kRightOff>(data)},
|
||||
};
|
||||
}
|
||||
|
||||
void StructType::Pack(std::span<uint8_t> data,
|
||||
const frc::DifferentialDriveWheelPositions& value) {
|
||||
wpi::PackStruct<kLeftOff>(data, value.left.value());
|
||||
wpi::PackStruct<kRightOff>(data, value.right.value());
|
||||
}
|
||||
Reference in New Issue
Block a user