3#include "math/eigen_interface.h"
9#include "math/geometry/rotation2d.h"
10#include "math/geometry/transform2d.h"
11#include "math/geometry/translation2d.h"
12#include "math/geometry/twist2d.h"
54 Pose2d(
const double &x,
const double &y,
const double &radians);
69 Pose2d(
const Eigen::Vector3d &pose_vector);
220Pose2d wrapped_mean(
const std::vector<Pose2d> &list);
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 translation2d.h:22