RIT VEXU Core API
Loading...
Searching...
No Matches
pose2d.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/transform2d.h"
11#include "math/geometry/translation2d.h"
12#include "math/geometry/twist2d.h"
13
23class Pose2d {
24 public:
28 constexpr Pose2d() : m_translation(Translation2d()), m_rotation(Rotation2d()) {}
29
37
45 Pose2d(const double &x, const double &y, const Rotation2d &rotation);
46
54 Pose2d(const double &x, const double &y, const double &radians);
55
62 Pose2d(const Translation2d &translation, const double &radians);
63
69 Pose2d(const Eigen::Vector3d &pose_vector);
70
77
83 double x() const;
84
90 double y() const;
91
97 Rotation2d rotation() const;
101 void setRotationRad(double rotRad);
102
106 void setRotationDeg(double rotDeg);
107
115 bool operator==(const Pose2d other) const;
116
123 Pose2d operator*(const double &scalar) const;
124
131 Pose2d operator/(const double &scalar) const;
132
139 Pose2d operator+(const Transform2d &transform) const;
140
146 Transform2d operator-(const Pose2d &other) const;
147
155 friend std::ostream &operator<<(std::ostream &os, const Pose2d &pose);
156
164 Pose2d relative_to(const Pose2d &other) const;
165
174 Pose2d transform_by(const Transform2d &transform) const;
175
193 Pose2d exp(const Twist2d &twist) const;
194
206 Twist2d log(const Pose2d &end_pose) const;
207
208 private:
209 Translation2d m_translation;
210 Rotation2d m_rotation;
211};
212
220Pose2d wrapped_mean(const std::vector<Pose2d> &list);
Definition pose2d.h:23
Pose2d relative_to(const Pose2d &other) const
Definition pose2d.cpp:156
Translation2d translation() const
Definition pose2d.cpp:62
Twist2d log(const Pose2d &end_pose) const
Definition pose2d.cpp:223
Pose2d operator*(const double &scalar) const
Definition pose2d.cpp:106
double x() const
Definition pose2d.cpp:69
bool operator==(const Pose2d other) const
Definition pose2d.cpp:96
friend std::ostream & operator<<(std::ostream &os, const Pose2d &pose)
Definition pose2d.cpp:143
Pose2d operator+(const Transform2d &transform) const
Definition pose2d.cpp:122
Pose2d operator/(const double &scalar) const
Definition pose2d.cpp:114
Rotation2d rotation() const
Definition pose2d.cpp:83
void setRotationRad(double rotRad)
Definition pose2d.cpp:85
void setRotationDeg(double rotDeg)
Definition pose2d.cpp:87
Pose2d transform_by(const Transform2d &transform) const
Definition pose2d.cpp:169
Transform2d operator-(const Pose2d &other) const
Definition pose2d.cpp:131
Pose2d exp(const Twist2d &twist) const
Definition pose2d.cpp:190
constexpr Pose2d()
Definition pose2d.h:28
double y() const
Definition pose2d.cpp:76
Definition rotation2d.h:25
Definition transform2d.h:23
Definition translation2d.h:22
Definition twist2d.h:19