#include <Rot2.h>
Classes | |
struct | ChartAtOrigin |
Private Member Functions | |
Rot2 & | normalize () |
Rot2 (double c, double s) | |
Private Attributes | |
double | c_ |
double | s_ |
Constructors and named constructors | |
Rot2 () | |
Rot2 (const Rot2 &r) | |
Rot2 (double theta) | |
Constructor from angle in radians == exponential map at identity. More... | |
static Rot2 | fromAngle (double theta) |
Named constructor from angle in radians. More... | |
static Rot2 | fromDegrees (double theta) |
Named constructor from angle in degrees. More... | |
static Rot2 | fromCosSin (double c, double s) |
Named constructor from cos(theta),sin(theta) pair. More... | |
static Rot2 | relativeBearing (const Point2 &d, OptionalJacobian< 1, 2 > H={}) |
static Rot2 | atan2 (double y, double x) |
static Rot2 | Random (std::mt19937 &rng) |
Testable | |
void | print (const std::string &s="theta") const |
bool | equals (const Rot2 &R, double tol=1e-9) const |
Group | |
Rot2 | inverse () const |
Rot2 | operator* (const Rot2 &R) const |
static Rot2 | Identity () |
Lie Group | |
Matrix1 | AdjointMap () const |
static Rot2 | Expmap (const Vector1 &v, ChartJacobian H={}) |
Exponential map at identity - create a rotation from canonical coordinates. More... | |
static Vector1 | Logmap (const Rot2 &r, ChartJacobian H={}) |
Log map at identity - return the canonical coordinates of this rotation. More... | |
static Matrix | ExpmapDerivative (const Vector &) |
Left-trivialized derivative of the exponential map. More... | |
static Matrix | LogmapDerivative (const Vector &) |
Left-trivialized derivative inverse of the exponential map. More... | |
Group Action on Point2 | |
Point2 | rotate (const Point2 &p, OptionalJacobian< 2, 1 > H1={}, OptionalJacobian< 2, 2 > H2={}) const |
Point2 | operator* (const Point2 &p) const |
Point2 | unrotate (const Point2 &p, OptionalJacobian< 2, 1 > H1={}, OptionalJacobian< 2, 2 > H2={}) const |
Standard Interface | |
Point2 | unit () const |
Creates a unit vector as a Point2. More... | |
double | theta () const |
double | degrees () const |
double | c () const |
double | s () const |
Matrix2 | matrix () const |
Matrix2 | transpose () const |
static Rot2 | ClosestTo (const Matrix2 &M) |
Additional Inherited Members | |
Public Types inherited from gtsam::LieGroup< Rot2, 1 > | |
enum | |
typedef OptionalJacobian< N, N > | ChartJacobian |
typedef Eigen::Matrix< double, N, N > | Jacobian |
typedef Eigen::Matrix< double, N, 1 > | TangentVector |
Public Member Functions inherited from gtsam::LieGroup< Rot2, 1 > | |
Rot2 | between (const Rot2 &g) const |
Rot2 | between (const Rot2 &g, ChartJacobian H1, ChartJacobian H2={}) const |
SOn | between (const SOn &g, DynamicJacobian H1, DynamicJacobian H2) const |
GTSAM_EXPORT SOn | between (const SOn &g, DynamicJacobian H1, DynamicJacobian H2) const |
Rot2 | compose (const Rot2 &g) const |
Rot2 | compose (const Rot2 &g, ChartJacobian H1, ChartJacobian H2={}) const |
SOn | compose (const SOn &g, DynamicJacobian H1, DynamicJacobian H2) const |
GTSAM_EXPORT SOn | compose (const SOn &g, DynamicJacobian H1, DynamicJacobian H2) const |
const Rot2 & | derived () const |
Rot2 | expmap (const TangentVector &v) const |
Rot2 | expmap (const TangentVector &v, ChartJacobian H1, ChartJacobian H2={}) 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={}) const |
localCoordinates with optional derivatives More... | |
TangentVector | logmap (const Rot2 &g) const |
TangentVector | logmap (const Rot2 &g, ChartJacobian H1, ChartJacobian H2={}) 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={}) const |
retract with optional derivatives More... | |
Static Public Member Functions inherited from gtsam::LieGroup< Rot2, 1 > | |
static TangentVector | LocalCoordinates (const Rot2 &g) |
LocalCoordinates at origin: possible in Lie group because it has an identity. More... | |
static TangentVector | LocalCoordinates (const Rot2 &g, ChartJacobian H) |
LocalCoordinates at origin with optional derivative. More... | |
static Rot2 | Retract (const TangentVector &v) |
Retract at origin: possible in Lie group because it has an identity. More... | |
static Rot2 | Retract (const TangentVector &v, ChartJacobian H) |
Retract at origin with optional derivative. More... | |
Rotation matrix NOTE: the angle theta is in radians unless explicitly stated
|
inlineprivate |
|
inline |
|
inline |
|
inline |
|
static |
|
static |
|
inline |
|
static |
|
inlinestatic |
|
static |
|
inlinestatic |
|
inline |
|
static |
Matrix2 gtsam::Rot2::matrix | ( | ) | const |
|
private |
void gtsam::Rot2::print | ( | const std::string & | s = "theta" | ) | const |
|
static |
|
static |
Point2 gtsam::Rot2::rotate | ( | const Point2 & | p, |
OptionalJacobian< 2, 1 > | H1 = {} , |
||
OptionalJacobian< 2, 2 > | H2 = {} |
||
) | const |
|
inline |
Matrix2 gtsam::Rot2::transpose | ( | ) | const |
|
inline |
Point2 gtsam::Rot2::unrotate | ( | const Point2 & | p, |
OptionalJacobian< 2, 1 > | H1 = {} , |
||
OptionalJacobian< 2, 2 > | H2 = {} |
||
) | const |
|
private |