RIT VEXU Core API
Loading...
Searching...
No Matches
pose2d.h
1#pragma once
2#undef __ARM_NEON__
3#undef __ARM_NEON
4#include <Eigen/Dense>
5
6#include <cmath>
7#include <iostream>
8#include <vector>
9
10#include "core/utils/math/geometry/rotation2d.h"
11#include "core/utils/math/geometry/transform2d.h"
12#include "core/utils/math/geometry/translation2d.h"
13#include "core/utils/math/geometry/twist2d.h"
14
24class Pose2d {
25 public:
29 constexpr Pose2d() : m_translation(Translation2d()), m_rotation(Rotation2d()) {}
30
38
46 Pose2d(const double &x, const double &y, const Rotation2d &rotation);
47
55 Pose2d(const double &x, const double &y, const double &radians);
56
63 Pose2d(const Translation2d &translation, const double &radians);
64
70 Pose2d(const Eigen::Vector3d &pose_vector);
71
78
84 double x() const;
85
91 double y() const;
92
98 Rotation2d rotation() const;
102 void setRotationRad(double rotRad);
103
107 void setRotationDeg(double rotDeg);
108
116 bool operator==(const Pose2d other) const;
117
124 Pose2d operator*(const double &scalar) const;
125
132 Pose2d operator/(const double &scalar) const;
133
140 Pose2d operator+(const Transform2d &transform) const;
141
147 Transform2d operator-(const Pose2d &other) const;
148
156 friend std::ostream &operator<<(std::ostream &os, const Pose2d &pose);
157
165 Pose2d relative_to(const Pose2d &other) const;
166
175 Pose2d transform_by(const Transform2d &transform) const;
176
194 Pose2d exp(const Twist2d &twist) const;
195
207 Twist2d log(const Pose2d &end_pose) const;
208
209 private:
210 Translation2d m_translation;
211 Rotation2d m_rotation;
212};
213
221Pose2d wrapped_mean(const std::vector<Pose2d> &list);
Definition pose2d.h:24
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:29
double y() const
Definition pose2d.cpp:76
Definition rotation2d.h:26
Definition transform2d.h:22
Definition translation2d.h:21
Definition twist2d.h:18