gtsam 4.2
gtsam
Loading...
Searching...
No Matches
gtsam::Unit3 Class Reference

Detailed Description

Represents a 3D point on a unit sphere.

Manifold

enum  CoordinatesMode { EXPMAP , RENORM }
size_t dim () const
 Dimensionality of tangent space = 2 DOF.
Unit3 retract (const Vector2 &v, OptionalJacobian< 2, 2 > H=boost::none) const
 The retract function.
Vector2 localCoordinates (const Unit3 &s) const
 The local coordinates function.
static size_t Dim ()
 Dimensionality of tangent space = 2 DOF.

Advanced Interface

class boost::serialization::access
 Serialization function.

Testable

std::ostream & operator<< (std::ostream &os, const Unit3 &pair)
void print (const std::string &s=std::string()) const
 The print fuction.
bool equals (const Unit3 &s, double tol=1e-9) const
 The equals function with tolerance.

Other functionality

Point3 operator* (double s, const Unit3 &d)
 Return scaled direction as Point3.
const Matrix32 & basis (OptionalJacobian< 6, 2 > H=boost::none) const
 Returns the local coordinate frame to tangent plane It is a 3*2 matrix [b1 b2] composed of two orthogonal directions tangent to the sphere at the current direction.
Matrix3 skew () const
 Return skew-symmetric associated with 3D point on unit sphere.
Point3 point3 (OptionalJacobian< 3, 2 > H=boost::none) const
 Return unit-norm Point3.
Vector3 unitVector (OptionalJacobian< 3, 2 > H=boost::none) const
 Return unit-norm Vector.
double dot (const Unit3 &q, OptionalJacobian< 1, 2 > H1=boost::none, OptionalJacobian< 1, 2 > H2=boost::none) const
 Return dot product with q.
Vector2 error (const Unit3 &q, OptionalJacobian< 2, 2 > H_q=boost::none) const
 Signed, vector-valued error between two directions.
Vector2 errorVector (const Unit3 &q, OptionalJacobian< 2, 2 > H_p=boost::none, OptionalJacobian< 2, 2 > H_q=boost::none) const
 Signed, vector-valued error between two directions NOTE(hayk): This method has zero derivatives if this (p) and q are orthogonal.
double distance (const Unit3 &q, OptionalJacobian< 1, 2 > H=boost::none) const
 Distance between two directions.
Unit3 cross (const Unit3 &q) const
 Cross-product between two Unit3s.
Point3 cross (const Point3 &q) const
 Cross-product w Point3.

Constructors

 Unit3 ()
 Default constructor.
 Unit3 (const Vector3 &p)
 Construct from point.
 Unit3 (double x, double y, double z)
 Construct from x,y,z.
 Unit3 (const Point2 &p, double f)
 Construct from 2D point in plane at focal length f Unit3(p,1) can be viewed as normalized homogeneous coordinates of 2D point.
 Unit3 (const Unit3 &u)
 Copy constructor.
Unit3operator= (const Unit3 &u)
 Copy assignment.
static Unit3 FromPoint3 (const Point3 &point, OptionalJacobian< 2, 3 > H=boost::none)
 Named constructor from Point3 with optional Jacobian.
static Unit3 Random (std::mt19937 &rng)
 Random direction, using boost::uniform_on_sphere Example: std::mt19937 engine(42); Unit3 unit = Unit3::Random(engine);.

Public Types

enum  { dimension = 2 }

Member Enumeration Documentation

◆ CoordinatesMode

Enumerator
EXPMAP 

Use the exponential map to retract.

RENORM 

Retract with vector addition and renormalize.

Member Function Documentation

◆ basis()

const Matrix32 & gtsam::Unit3::basis ( OptionalJacobian< 6, 2 > H = boost::none) const

Returns the local coordinate frame to tangent plane It is a 3*2 matrix [b1 b2] composed of two orthogonal directions tangent to the sphere at the current direction.

Provides derivatives of the basis with the two basis vectors stacked up as a 6x1.

◆ error()

Vector2 gtsam::Unit3::error ( const Unit3 & q,
OptionalJacobian< 2, 2 > H_q = boost::none ) const

Signed, vector-valued error between two directions.

Deprecated
, errorVector has the proper derivatives, this confusingly has only the second.

The documentation for this class was generated from the following files:
  • /tmp/gtsam-4.2-docs.H5EUbA/src/gtsam/geometry/Unit3.h
  • /tmp/gtsam-4.2-docs.H5EUbA/src/gtsam/geometry/Unit3.cpp