gtsam  4.0.0
gtsam
gtsam::Rot2 Class Reference
+ Inheritance diagram for gtsam::Rot2:

Constructors and named constructors

 Rot2 ()
 default constructor, zero rotation
 
 Rot2 (double theta)
 Constructor from angle in radians == exponential map at identity.
 
static Rot2 fromAngle (double theta)
 Named constructor from angle in radians.
 
static Rot2 fromDegrees (double theta)
 Named constructor from angle in degrees.
 
static Rot2 fromCosSin (double c, double s)
 Named constructor from cos(theta),sin(theta) pair, will not normalize!
 
static Rot2 relativeBearing (const Point2 &d, OptionalJacobian< 1, 2 > H=boost::none)
 Named constructor with derivative Calculate relative bearing to a landmark in local coordinate frame. More...
 
static Rot2 atan2 (double y, double x)
 Named constructor that behaves as atan2, i.e., y,x order (!) and normalizes.
 

Group

Rot2 inverse () const
 The inverse rotation - negative angle.
 
Rot2 operator * (const Rot2 &R) const
 Compose - make a new rotation by adding angles.
 
static Rot2 identity ()
 identity
 

Lie Group

Matrix1 AdjointMap () const
 Calculate Adjoint map.
 
static Rot2 Expmap (const Vector1 &v, ChartJacobian H=boost::none)
 Exponential map at identity - create a rotation from canonical coordinates.
 
static Vector1 Logmap (const Rot2 &r, ChartJacobian H=boost::none)
 Log map at identity - return the canonical coordinates of this rotation.
 
static Matrix ExpmapDerivative (const Vector &)
 Left-trivialized derivative of the exponential map.
 
static Matrix LogmapDerivative (const Vector &)
 Left-trivialized derivative inverse of the exponential map.
 

Standard Interface

class boost::serialization::access
 Serialization function.
 
Point2 unit () const
 Creates a unit vector as a Point2.
 
double theta () const
 return angle (RADIANS)
 
double degrees () const
 return angle (DEGREES)
 
double c () const
 return cos
 
double s () const
 return sin
 
Matrix2 matrix () const
 return 2*2 rotation matrix
 
Matrix2 transpose () const
 return 2*2 transpose (inverse) rotation matrix
 

Public Member Functions

Testable
void print (const std::string &s="theta") const
 print
 
bool equals (const Rot2 &R, double tol=1e-9) const
 equals with an tolerance
 
Group Action on Point2
Point2 rotate (const Point2 &p, OptionalJacobian< 2, 1 > H1=boost::none, OptionalJacobian< 2, 2 > H2=boost::none) const
 rotate point from rotated coordinate frame to world \( p^w = R_c^w p^c \)
 
Point2 operator * (const Point2 &p) const
 syntactic sugar for rotate
 
Point2 unrotate (const Point2 &p, OptionalJacobian< 2, 1 > H1=boost::none, OptionalJacobian< 2, 2 > H2=boost::none) const
 rotate point from world to rotated frame \( p^c = (R_c^w)^T p^w \)
 
- Public Member Functions inherited from gtsam::LieGroup< Rot2, 1 >
 BOOST_STATIC_ASSERT_MSG (N !=Eigen::Dynamic, "LieGroup not yet specialized for dynamically sized types.")
 
const Rot2derived () const
 
Rot2 compose (const Rot2 &g) const
 
Rot2 compose (const Rot2 &g, ChartJacobian H1, ChartJacobian H2=boost::none) const
 
Rot2 between (const Rot2 &g) const
 
Rot2 between (const Rot2 &g, ChartJacobian H1, ChartJacobian H2=boost::none) const
 
Rot2 inverse (ChartJacobian H) const
 
Rot2 expmap (const TangentVector &v) const
 expmap as required by manifold concept Applies exponential map to v and composes with *this
 
Rot2 expmap (const TangentVector &v, ChartJacobian H1, ChartJacobian H2=boost::none) const
 expmap with optional derivatives
 
TangentVector logmap (const Rot2 &g) const
 logmap as required by manifold concept Applies logarithmic map to group element that takes *this to g
 
TangentVector logmap (const Rot2 &g, ChartJacobian H1, ChartJacobian H2=boost::none) const
 logmap with optional derivatives
 
Rot2 retract (const TangentVector &v) const
 retract as required by manifold concept: applies v at *this
 
Rot2 retract (const TangentVector &v, ChartJacobian H1, ChartJacobian H2=boost::none) const
 retract with optional derivatives
 
TangentVector localCoordinates (const Rot2 &g) const
 localCoordinates as required by manifold concept: finds tangent vector between *this and g
 
TangentVector localCoordinates (const Rot2 &g, ChartJacobian H1, ChartJacobian H2=boost::none) const
 localCoordinates with optional derivatives
 

Classes

struct  ChartAtOrigin
 

Additional Inherited Members

- Static Public Member Functions inherited from gtsam::LieGroup< Rot2, 1 >
static Rot2 Retract (const TangentVector &v)
 Retract at origin: possible in Lie group because it has an identity.
 
static Rot2 Retract (const TangentVector &v, ChartJacobian H)
 Retract at origin with optional derivative.
 
static TangentVector LocalCoordinates (const Rot2 &g)
 LocalCoordinates at origin: possible in Lie group because it has an identity.
 
static TangentVector LocalCoordinates (const Rot2 &g, ChartJacobian H)
 LocalCoordinates at origin with optional derivative.
 
- 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
 

Member Function Documentation

◆ relativeBearing()

Rot2 gtsam::Rot2::relativeBearing ( const Point2 d,
OptionalJacobian< 1, 2 >  H = boost::none 
)
static

Named constructor with derivative Calculate relative bearing to a landmark in local coordinate frame.

Parameters
d2D location of landmark
Hoptional reference for Jacobian
Returns
2D rotation \( \in SO(2) \)

The documentation for this class was generated from the following files: