RIT VEXU Core API
Loading...
Searching...
No Matches
twist2d.h
1#pragma once
2#include <Eigen/Dense>
3
4#include <cmath>
5#include <iostream>
6#include <vector>
7
18class Twist2d {
19 public:
23 constexpr Twist2d();
24
32 Twist2d(const double &dx, const double &dy, const double &dtheta);
33
39 Twist2d(const Eigen::Vector3d &twist_vector);
40
46 double dx() const;
47
53 double dy() const;
54
60 double dtheta() const;
61
69 bool operator==(const Twist2d &other) const;
70
76 Twist2d operator*(const double &scalar) const;
77
83 Twist2d operator/(const double &scalar) const;
84
92 friend std::ostream &operator<<(std::ostream &os, const Twist2d &twist);
93
94 private:
95 double m_dx;
96 double m_dy;
97 double m_dtheta;
98};
friend std::ostream & operator<<(std::ostream &os, const Twist2d &twist)
Definition twist2d.cpp:86
double dtheta() const
Definition twist2d.cpp:49
constexpr Twist2d()
Definition twist2d.cpp:11
double dy() const
Definition twist2d.cpp:42
double dx() const
Definition twist2d.cpp:35
bool operator==(const Twist2d &other) const
Definition twist2d.cpp:58
Twist2d operator*(const double &scalar) const
Definition twist2d.cpp:68
Twist2d operator/(const double &scalar) const
Definition twist2d.cpp:77