RIT VEXU Core API
Loading...
Searching...
No Matches
translation2d.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
11class Rotation2d;
12
23 public:
27
28 constexpr Translation2d() : m_x(0), m_y(0) {}
35 Translation2d(const double &x, const double &y);
36
42 Translation2d(const Eigen::Vector2d &vector);
43
50 Translation2d(const double &r, const Rotation2d &theta);
51
57 double x() const;
58
62 void setX(double x);
63
69 double y() const;
70
74 void setY(double y);
75
81 Rotation2d theta() const;
82
88 Eigen::Vector2d as_vector() const;
89
95 double norm() const;
96
102 Translation2d normalize() const;
103
109 double distance(const Translation2d &other) const;
110
122 Translation2d rotate_by(const Rotation2d &rotation) const;
123
135 Translation2d rotate_around(const Translation2d &other, const Rotation2d &rotation) const;
136
147 Translation2d operator+(const Translation2d &other) const;
148
159 Translation2d operator-(const Translation2d &other) const;
160
170 Translation2d operator-() const;
171
182 Translation2d operator*(const double &scalar) const;
183
194 Translation2d operator/(const double &scalar) const;
195
205 double operator*(const Translation2d &other) const;
206
215 bool operator==(const Translation2d &other) const;
216
224 friend std::ostream &operator<<(std::ostream &os, const Translation2d &translation);
225
226 private:
227 double m_x;
228 double m_y;
229};
230
238Translation2d mean(const std::vector<Translation2d> &list);
Definition rotation2d.h:25
Definition translation2d.h:22
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:28
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