22#include <frc/geometry/Pose3d.h>
23#include <frc/geometry/Rotation3d.h>
24#include <frc/geometry/Translation3d.h>
30 const frc::Translation3d& newTrl)
31 : trl{newTrl}, rot{newRot} {}
34 : trl{last.Translation() - initial.Translation().RotateBy(
35 last.Rotation() - initial.Rotation())},
36 rot{last.Rotation() - initial.Rotation()} {}
47 frc::Rotation3d invRot = -rot;
48 frc::Translation3d invTrl = -(trl.RotateBy(invRot));
52 frc::Transform3d
GetTransform()
const {
return frc::Transform3d{trl, rot}; }
58 frc::Translation3d
Apply(
const frc::Translation3d& trlToApply)
const {
59 return trlToApply.RotateBy(rot) + trl;
63 const std::vector<frc::Translation3d>& trls)
const {
64 std::vector<frc::Translation3d> retVal;
65 retVal.reserve(trls.size());
66 for (
const auto& currentTrl : trls) {
67 retVal.emplace_back(
Apply(currentTrl));
72 frc::Rotation3d
Apply(
const frc::Rotation3d& rotToApply)
const {
73 return rotToApply + rot;
77 const std::vector<frc::Rotation3d>& rots)
const {
78 std::vector<frc::Rotation3d> retVal;
79 retVal.reserve(rots.size());
80 for (
const auto& currentRot : rots) {
81 retVal.emplace_back(
Apply(currentRot));
86 frc::Pose3d
Apply(
const frc::Pose3d& poseToApply)
const {
87 return frc::Pose3d{
Apply(poseToApply.Translation()),
88 Apply(poseToApply.Rotation())};
92 const std::vector<frc::Pose3d>& poses)
const {
93 std::vector<frc::Pose3d> retVal;
94 retVal.reserve(poses.size());
95 for (
const auto& currentPose : poses) {
96 retVal.emplace_back(
Apply(currentPose));
102 const frc::Translation3d trl;
103 const frc::Rotation3d rot;
Definition VisionEstimation.h:32