RIT VEXU Core API
Loading...
Searching...
No Matches
transform2d.h
1#pragma once
2
3#include "math/eigen_interface.h"
4
5#include <cmath>
6#include <iostream>
7#include <vector>
8
9#include "math/geometry/rotation2d.h"
10#include "math/geometry/translation2d.h"
11
12class Pose2d;
13
24 public:
28 constexpr Transform2d();
29
37
45 Transform2d(const double &x, const double &y, const Rotation2d &rotation);
46
54 Transform2d(const double &x, const double &y, const double &radians);
55
62 Transform2d(const Translation2d &translation, const double &radians);
63
69 Transform2d(const Eigen::Vector3d &transform_vector);
70
77 Transform2d(const Pose2d &start, const Pose2d &end);
78
85
91 double x() const;
92
98 double y() const;
99
105 Rotation2d rotation() const;
106
112 Transform2d inverse() const;
113
119 Transform2d operator*(const double &scalar) const;
120
126 Transform2d operator/(const double &scalar) const;
127
133 Transform2d operator-() const;
134
142 bool operator==(const Transform2d &other) const;
143
151 friend std::ostream &operator<<(std::ostream &os, const Transform2d &transform);
152
153 private:
154 Translation2d m_translation;
155 Rotation2d m_rotation;
156};
Definition pose2d.h:23
Definition rotation2d.h:25
Transform2d inverse() const
Definition transform2d.cpp:105
friend std::ostream & operator<<(std::ostream &os, const Transform2d &transform)
Definition transform2d.cpp:148
bool operator==(const Transform2d &other) const
Definition transform2d.cpp:137
Transform2d operator/(const double &scalar) const
Definition transform2d.cpp:121
Rotation2d rotation() const
Definition transform2d.cpp:98
double x() const
Definition transform2d.cpp:84
double y() const
Definition transform2d.cpp:91
Translation2d translation() const
Definition transform2d.cpp:77
Transform2d operator*(const double &scalar) const
Definition transform2d.cpp:112
constexpr Transform2d()
Definition transform2d.cpp:14
Transform2d operator-() const
Definition transform2d.cpp:128
Definition translation2d.h:22