#include <Rot2.h>
|
|
void | print (const std::string &s="theta") const |
|
bool | equals (const Rot2 &R, double tol=1e-9) const |
|
|
Point2 | rotate (const Point2 &p, OptionalJacobian< 2, 1 > H1=boost::none, OptionalJacobian< 2, 2 > H2=boost::none) const |
|
Point2 | operator* (const Point2 &p) const |
|
Point2 | unrotate (const Point2 &p, OptionalJacobian< 2, 1 > H1=boost::none, OptionalJacobian< 2, 2 > H2=boost::none) const |
|
Rot2 | between (const Rot2 &g) const |
|
Rot2 | between (const Rot2 &g, ChartJacobian H1, ChartJacobian H2=boost::none) const |
|
Rot2 | compose (const Rot2 &g) const |
|
Rot2 | compose (const Rot2 &g, ChartJacobian H1, ChartJacobian H2=boost::none) const |
|
const Rot2 & | derived () const |
|
Rot2 | expmap (const TangentVector &v) const |
|
Rot2 | expmap (const TangentVector &v, ChartJacobian H1, ChartJacobian H2=boost::none) const |
| expmap with optional derivatives More...
|
|
Rot2 | inverse (ChartJacobian H) const |
|
TangentVector | localCoordinates (const Rot2 &g) const |
| localCoordinates as required by manifold concept: finds tangent vector between *this and g More...
|
|
TangentVector | localCoordinates (const Rot2 &g, ChartJacobian H1, ChartJacobian H2=boost::none) const |
| localCoordinates with optional derivatives More...
|
|
TangentVector | logmap (const Rot2 &g) const |
|
TangentVector | logmap (const Rot2 &g, ChartJacobian H1, ChartJacobian H2=boost::none) const |
| logmap with optional derivatives More...
|
|
Rot2 | retract (const TangentVector &v) const |
| retract as required by manifold concept: applies v at *this More...
|
|
Rot2 | retract (const TangentVector &v, ChartJacobian H1, ChartJacobian H2=boost::none) const |
| retract with optional derivatives More...
|
|
Definition at line 35 of file Rot2.h.
gtsam::Rot2::Rot2 |
( |
double |
c, |
|
|
double |
s |
|
) |
| |
|
inlineprivate |
private constructor from cos/sin
Definition at line 44 of file Rot2.h.
default constructor, zero rotation
Definition at line 52 of file Rot2.h.
gtsam::Rot2::Rot2 |
( |
double |
theta | ) |
|
|
inline |
Constructor from angle in radians == exponential map at identity.
Definition at line 55 of file Rot2.h.
Matrix1 gtsam::Rot2::AdjointMap |
( |
| ) |
const |
|
inline |
Calculate Adjoint map
Definition at line 128 of file Rot2.h.
Rot2 gtsam::Rot2::atan2 |
( |
double |
y, |
|
|
double |
x |
|
) |
| |
|
static |
Named constructor that behaves as atan2, i.e., y,x order (!) and normalizes
Definition at line 37 of file Rot2.cpp.
double gtsam::Rot2::c |
( |
| ) |
const |
|
inline |
return cos
Definition at line 194 of file Rot2.h.
double gtsam::Rot2::degrees |
( |
| ) |
const |
|
inline |
return angle (DEGREES)
Definition at line 188 of file Rot2.h.
bool gtsam::Rot2::equals |
( |
const Rot2 & |
R, |
|
|
double |
tol = 1e-9 |
|
) |
| const |
equals with an tolerance
Definition at line 55 of file Rot2.cpp.
Exponential map at identity - create a rotation from canonical coordinates.
Definition at line 71 of file Rot2.cpp.
static Matrix gtsam::Rot2::ExpmapDerivative |
( |
const Vector & |
| ) |
|
|
inlinestatic |
Left-trivialized derivative of the exponential map.
Definition at line 131 of file Rot2.h.
static Rot2 gtsam::Rot2::fromAngle |
( |
double |
theta | ) |
|
|
inlinestatic |
Named constructor from angle in radians.
Definition at line 58 of file Rot2.h.
Rot2 gtsam::Rot2::fromCosSin |
( |
double |
c, |
|
|
double |
s |
|
) |
| |
|
static |
Named constructor from cos(theta),sin(theta) pair, will not normalize!
Definition at line 27 of file Rot2.cpp.
static Rot2 gtsam::Rot2::fromDegrees |
( |
double |
theta | ) |
|
|
inlinestatic |
Named constructor from angle in degrees.
Definition at line 63 of file Rot2.h.
static Rot2 gtsam::Rot2::identity |
( |
| ) |
|
|
inlinestatic |
identity
Definition at line 107 of file Rot2.h.
Rot2 gtsam::Rot2::inverse |
( |
| ) |
const |
|
inline |
The inverse rotation - negative angle
Definition at line 110 of file Rot2.h.
Log map at identity - return the canonical coordinates of this rotation.
Definition at line 81 of file Rot2.cpp.
static Matrix gtsam::Rot2::LogmapDerivative |
( |
const Vector & |
| ) |
|
|
inlinestatic |
Left-trivialized derivative inverse of the exponential map.
Definition at line 136 of file Rot2.h.
Matrix2 gtsam::Rot2::matrix |
( |
| ) |
const |
return 2*2 rotation matrix
Definition at line 89 of file Rot2.cpp.
Rot2 & gtsam::Rot2::normalize |
( |
void |
| ) |
|
|
private |
normalize to make sure cos and sin form unit vector
Definition at line 60 of file Rot2.cpp.
Rot2 gtsam::Rot2::operator* |
( |
const Rot2 & |
R | ) |
const |
|
inline |
Compose - make a new rotation by adding angles
Definition at line 113 of file Rot2.h.
syntactic sugar for rotate
Definition at line 163 of file Rot2.h.
void gtsam::Rot2::print |
( |
const std::string & |
s = "theta" | ) |
const |
Rot2 gtsam::Rot2::Random |
( |
std::mt19937 & |
rng | ) |
|
|
static |
Random, generates random angle [-p,pi] Example: std::mt19937 engine(42); Unit3 unit = Unit3::Random(engine);
Definition at line 43 of file Rot2.cpp.
Named constructor with derivative Calculate relative bearing to a landmark in local coordinate frame
- Parameters
-
d | 2D location of landmark |
H | optional reference for Jacobian |
- Returns
- 2D rotation
Definition at line 123 of file Rot2.cpp.
rotate point from rotated coordinate frame to world
Definition at line 104 of file Rot2.cpp.
double gtsam::Rot2::s |
( |
| ) |
const |
|
inline |
return sin
Definition at line 199 of file Rot2.h.
template<class ARCHIVE >
void gtsam::Rot2::serialize |
( |
ARCHIVE & |
ar, |
|
|
const unsigned |
int |
|
) |
| |
|
inlineprivate |
double gtsam::Rot2::theta |
( |
| ) |
const |
|
inline |
return angle (RADIANS)
Definition at line 183 of file Rot2.h.
Matrix2 gtsam::Rot2::transpose |
( |
| ) |
const |
return 2*2 transpose (inverse) rotation matrix
Definition at line 96 of file Rot2.cpp.
Point2 gtsam::Rot2::unit |
( |
| ) |
const |
|
inline |
Creates a unit vector as a Point2.
Definition at line 178 of file Rot2.h.
rotate point from world to rotated frame
Definition at line 114 of file Rot2.cpp.
friend class boost::serialization::access |
|
friend |
Serialization function
Definition at line 211 of file Rot2.h.
we store cos(theta) and sin(theta)
Definition at line 38 of file Rot2.h.
The documentation for this class was generated from the following files: