RIT VEXU Core API
Loading...
Searching...
No Matches
transform2d.h
1#pragma once
2#include <Eigen/Dense>
3
4#include <cmath>
5#include <iostream>
6#include <vector>
7
8#include "core/utils/math/geometry/rotation2d.h"
9#include "core/utils/math/geometry/translation2d.h"
10
11class Pose2d;
12
23 public:
27 constexpr Transform2d();
28
36
44 Transform2d(const double &x, const double &y, const Rotation2d &rotation);
45
53 Transform2d(const double &x, const double &y, const double &radians);
54
61 Transform2d(const Translation2d &translation, const double &radians);
62
68 Transform2d(const Eigen::Vector3d &transform_vector);
69
76 Transform2d(const Pose2d &start, const Pose2d &end);
77
84
90 double x() const;
91
97 double y() const;
98
104 Rotation2d rotation() const;
105
111 Transform2d inverse() const;
112
118 Transform2d operator*(const double &scalar) const;
119
125 Transform2d operator/(const double &scalar) const;
126
132 Transform2d operator-() const;
133
141 bool operator==(const Transform2d &other) const;
142
150 friend std::ostream &operator<<(std::ostream &os, const Transform2d &transform);
151
152 private:
153 Translation2d m_translation;
154 Rotation2d m_rotation;
155};
Definition pose2d.h:24
Definition rotation2d.h:26
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:21