RIT VEXU Core API
Loading...
Searching...
No Matches
translation2d.h
1#pragma once
2
3#include <Eigen/Dense>
4#include <cmath>
5#include <iostream>
6#include <vector>
7
8#include "core/utils/math/geometry/rotation2d.h"
9
10class Rotation2d;
11
22 public:
26
27 constexpr Translation2d() : m_x(0), m_y(0) {}
34 Translation2d(const double &x, const double &y);
35
41 Translation2d(const Eigen::Vector2d &vector);
42
49 Translation2d(const double &r, const Rotation2d &theta);
50
56 double x() const;
57
61 void setX(double x);
62
68 double y() const;
69
73 void setY(double y);
74
80 Rotation2d theta() const;
81
87 Eigen::Vector2d as_vector() const;
88
94 double norm() const;
95
101 Translation2d normalize() const;
102
108 double distance(const Translation2d &other) const;
109
121 Translation2d rotate_by(const Rotation2d &rotation) const;
122
134 Translation2d rotate_around(const Translation2d &other, const Rotation2d &rotation) const;
135
146 Translation2d operator+(const Translation2d &other) const;
147
158 Translation2d operator-(const Translation2d &other) const;
159
169 Translation2d operator-() const;
170
181 Translation2d operator*(const double &scalar) const;
182
193 Translation2d operator/(const double &scalar) const;
194
204 double operator*(const Translation2d &other) const;
205
214 bool operator==(const Translation2d &other) const;
215
223 friend std::ostream &operator<<(std::ostream &os, const Translation2d &translation);
224
225 private:
226 double m_x;
227 double m_y;
228};
229
237Translation2d mean(const std::vector<Translation2d> &list);
Definition rotation2d.h:26
Definition translation2d.h:21
Translation2d operator/(const double &scalar) const
Definition translation2d.cpp:171
bool operator==(const Translation2d &other) const
Definition translation2d.cpp:192
friend std::ostream & operator<<(std::ostream &os, const Translation2d &translation)
Definition translation2d.cpp:203
Translation2d rotate_around(const Translation2d &other, const Rotation2d &rotation) const
Definition translation2d.cpp:109
Translation2d operator-() const
Definition translation2d.cpp:147
Translation2d normalize() const
Definition translation2d.cpp:72
double distance(const Translation2d &other) const
Definition translation2d.cpp:79
constexpr Translation2d()
Definition translation2d.h:27
double x() const
Definition translation2d.cpp:37
Translation2d rotate_by(const Rotation2d &rotation) const
Definition translation2d.cpp:94
Eigen::Vector2d as_vector() const
Definition translation2d.cpp:58
Rotation2d theta() const
Definition translation2d.cpp:51
void setX(double x)
void setY(double y)
double y() const
Definition translation2d.cpp:44
double norm() const
Definition translation2d.cpp:65
Translation2d operator+(const Translation2d &other) const
Definition translation2d.cpp:124
Translation2d operator*(const double &scalar) const
Definition translation2d.cpp:159