PhotonVision C++ dev-v2025.0.0-beta-8-2-gbd1c5c03
Loading...
Searching...
No Matches
RotTrlTransform3d.h
Go to the documentation of this file.
1/*
2 * Copyright (C) Photon Vision.
3 *
4 * This program is free software: you can redistribute it and/or modify
5 * it under the terms of the GNU General Public License as published by
6 * the Free Software Foundation, either version 3 of the License, or
7 * (at your option) any later version.
8 *
9 * This program is distributed in the hope that it will be useful,
10 * but WITHOUT ANY WARRANTY; without even the implied warranty of
11 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 * GNU General Public License for more details.
13 *
14 * You should have received a copy of the GNU General Public License
15 * along with this program. If not, see <https://www.gnu.org/licenses/>.
16 */
17
18#pragma once
19
20#include <vector>
21
22#include <frc/geometry/Pose3d.h>
23#include <frc/geometry/Rotation3d.h>
24#include <frc/geometry/Translation3d.h>
25
26namespace photon {
28 public:
29 RotTrlTransform3d(const frc::Rotation3d& newRot,
30 const frc::Translation3d& newTrl)
31 : trl{newTrl}, rot{newRot} {}
32
33 RotTrlTransform3d(const frc::Pose3d& initial, const frc::Pose3d& last)
34 : trl{last.Translation() - initial.Translation().RotateBy(
35 last.Rotation() - initial.Rotation())},
36 rot{last.Rotation() - initial.Rotation()} {}
37 explicit RotTrlTransform3d(const frc::Transform3d& trf)
38 : RotTrlTransform3d(trf.Rotation(), trf.Translation()) {}
40 : RotTrlTransform3d(frc::Rotation3d{}, frc::Translation3d{}) {}
41
42 static RotTrlTransform3d MakeRelativeTo(const frc::Pose3d& pose) {
43 return RotTrlTransform3d{pose.Rotation(), pose.Translation()}.Inverse();
44 }
45
47 frc::Rotation3d invRot = -rot;
48 frc::Translation3d invTrl = -(trl.RotateBy(invRot));
49 return RotTrlTransform3d{invRot, invTrl};
50 }
51
52 frc::Transform3d GetTransform() const { return frc::Transform3d{trl, rot}; }
53
54 frc::Translation3d GetTranslation() const { return trl; }
55
56 frc::Rotation3d GetRotation() const { return rot; }
57
58 frc::Translation3d Apply(const frc::Translation3d& trlToApply) const {
59 return trlToApply.RotateBy(rot) + trl;
60 }
61
62 std::vector<frc::Translation3d> ApplyTrls(
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));
68 }
69 return retVal;
70 }
71
72 frc::Rotation3d Apply(const frc::Rotation3d& rotToApply) const {
73 return rotToApply + rot;
74 }
75
76 std::vector<frc::Rotation3d> ApplyTrls(
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));
82 }
83 return retVal;
84 }
85
86 frc::Pose3d Apply(const frc::Pose3d& poseToApply) const {
87 return frc::Pose3d{Apply(poseToApply.Translation()),
88 Apply(poseToApply.Rotation())};
89 }
90
91 std::vector<frc::Pose3d> ApplyPoses(
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));
97 }
98 return retVal;
99 }
100
101 private:
102 const frc::Translation3d trl;
103 const frc::Rotation3d rot;
104};
105} // namespace photon
Definition RotTrlTransform3d.h:27
RotTrlTransform3d Inverse() const
Definition RotTrlTransform3d.h:46
std::vector< frc::Rotation3d > ApplyTrls(const std::vector< frc::Rotation3d > &rots) const
Definition RotTrlTransform3d.h:76
RotTrlTransform3d(const frc::Transform3d &trf)
Definition RotTrlTransform3d.h:37
RotTrlTransform3d(const frc::Pose3d &initial, const frc::Pose3d &last)
Definition RotTrlTransform3d.h:33
RotTrlTransform3d()
Definition RotTrlTransform3d.h:39
static RotTrlTransform3d MakeRelativeTo(const frc::Pose3d &pose)
Definition RotTrlTransform3d.h:42
frc::Transform3d GetTransform() const
Definition RotTrlTransform3d.h:52
frc::Pose3d Apply(const frc::Pose3d &poseToApply) const
Definition RotTrlTransform3d.h:86
std::vector< frc::Pose3d > ApplyPoses(const std::vector< frc::Pose3d > &poses) const
Definition RotTrlTransform3d.h:91
frc::Rotation3d Apply(const frc::Rotation3d &rotToApply) const
Definition RotTrlTransform3d.h:72
frc::Translation3d Apply(const frc::Translation3d &trlToApply) const
Definition RotTrlTransform3d.h:58
std::vector< frc::Translation3d > ApplyTrls(const std::vector< frc::Translation3d > &trls) const
Definition RotTrlTransform3d.h:62
frc::Rotation3d GetRotation() const
Definition RotTrlTransform3d.h:56
RotTrlTransform3d(const frc::Rotation3d &newRot, const frc::Translation3d &newTrl)
Definition RotTrlTransform3d.h:29
frc::Translation3d GetTranslation() const
Definition RotTrlTransform3d.h:54
Definition VisionEstimation.h:32