Public Types | Private Attributes | List of all members
gtsam::Unit3 Class Reference

Represents a 3D point on a unit sphere. More...

#include <Unit3.h>

Public Types

enum  { dimension = 2 }
 

Private Attributes

boost::optional< Matrix32 > B_
 Cached basis. More...
 
boost::optional< Matrix62 > H_B_
 Cached basis derivative. More...
 
Vector3 p_
 The location of the point on the unit sphere. More...
 

Constructors

 Unit3 ()
 Default constructor. More...
 
 Unit3 (const Vector3 &p)
 Construct from point. More...
 
 Unit3 (double x, double y, double z)
 Construct from x,y,z. More...
 
 Unit3 (const Point2 &p, double f)
 
 Unit3 (const Unit3 &u)
 Copy constructor. More...
 
Unit3operator= (const Unit3 &u)
 Copy assignment. More...
 
static GTSAM_EXPORT Unit3 FromPoint3 (const Point3 &point, OptionalJacobian< 2, 3 > H=boost::none)
 Named constructor from Point3 with optional Jacobian. More...
 
static GTSAM_EXPORT Unit3 Random (std::mt19937 &rng)
 

Testable

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

Other functionality

Point3 operator* (double s, const Unit3 &d)
 Return scaled direction as Point3. More...
 
GTSAM_EXPORT const Matrix32 & basis (OptionalJacobian< 6, 2 > H=boost::none) const
 
GTSAM_EXPORT Matrix3 skew () const
 Return skew-symmetric associated with 3D point on unit sphere. More...
 
GTSAM_EXPORT Point3 point3 (OptionalJacobian< 3, 2 > H=boost::none) const
 Return unit-norm Point3. More...
 
GTSAM_EXPORT Vector3 unitVector (OptionalJacobian< 3, 2 > H=boost::none) const
 Return unit-norm Vector. More...
 
GTSAM_EXPORT double dot (const Unit3 &q, OptionalJacobian< 1, 2 > H1=boost::none, OptionalJacobian< 1, 2 > H2=boost::none) const
 Return dot product with q. More...
 
GTSAM_EXPORT Vector2 error (const Unit3 &q, OptionalJacobian< 2, 2 > H_q=boost::none) const
 
GTSAM_EXPORT Vector2 errorVector (const Unit3 &q, OptionalJacobian< 2, 2 > H_p=boost::none, OptionalJacobian< 2, 2 > H_q=boost::none) const
 
GTSAM_EXPORT double distance (const Unit3 &q, OptionalJacobian< 1, 2 > H=boost::none) const
 Distance between two directions. More...
 
Unit3 cross (const Unit3 &q) const
 Cross-product between two Unit3s. More...
 
Point3 cross (const Point3 &q) const
 Cross-product w Point3. More...
 

Manifold

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

Advanced Interface

class boost::serialization::access
 
template<class ARCHIVE >
void serialize (ARCHIVE &ar, const unsigned int)
 

Detailed Description

Represents a 3D point on a unit sphere.

Definition at line 42 of file Unit3.h.

Member Enumeration Documentation

anonymous enum
Enumerator
dimension 

Definition at line 56 of file Unit3.h.

Enumerator
EXPMAP 

Use the exponential map to retract.

RENORM 

Retract with vector addition and renormalize.

Definition at line 192 of file Unit3.h.

Constructor & Destructor Documentation

gtsam::Unit3::Unit3 ( )
inline

Default constructor.

Definition at line 64 of file Unit3.h.

gtsam::Unit3::Unit3 ( const Vector3 p)
inlineexplicit

Construct from point.

Definition at line 69 of file Unit3.h.

gtsam::Unit3::Unit3 ( double  x,
double  y,
double  z 
)
inline

Construct from x,y,z.

Definition at line 74 of file Unit3.h.

gtsam::Unit3::Unit3 ( const Point2 p,
double  f 
)
inlineexplicit

Construct from 2D point in plane at focal length f Unit3(p,1) can be viewed as normalized homogeneous coordinates of 2D point

Definition at line 81 of file Unit3.h.

gtsam::Unit3::Unit3 ( const Unit3 u)
inline

Copy constructor.

Definition at line 86 of file Unit3.h.

Member Function Documentation

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.

Definition at line 76 of file Unit3.cpp.

Unit3 gtsam::Unit3::cross ( const Unit3 q) const
inline

Cross-product between two Unit3s.

Definition at line 168 of file Unit3.h.

Point3 gtsam::Unit3::cross ( const Point3 q) const
inline

Cross-product w Point3.

Definition at line 173 of file Unit3.h.

static size_t gtsam::Unit3::Dim ( )
inlinestatic

Dimensionality of tangent space = 2 DOF.

Definition at line 183 of file Unit3.h.

size_t gtsam::Unit3::dim ( ) const
inline

Dimensionality of tangent space = 2 DOF.

Definition at line 188 of file Unit3.h.

double gtsam::Unit3::distance ( const Unit3 q,
OptionalJacobian< 1, 2 >  H = boost::none 
) const

Distance between two directions.

Definition at line 237 of file Unit3.cpp.

double gtsam::Unit3::dot ( const Unit3 q,
OptionalJacobian< 1, 2 >  H1 = boost::none,
OptionalJacobian< 1, 2 >  H2 = boost::none 
) const

Return dot product with q.

Definition at line 166 of file Unit3.cpp.

bool gtsam::Unit3::equals ( const Unit3 s,
double  tol = 1e-9 
) const
inline

The equals function with tolerance.

Definition at line 121 of file Unit3.h.

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.

Definition at line 191 of file Unit3.cpp.

Vector2 gtsam::Unit3::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.

Definition at line 201 of file Unit3.cpp.

Unit3 gtsam::Unit3::FromPoint3 ( const Point3 point,
OptionalJacobian< 2, 3 >  H = boost::none 
)
static

Named constructor from Point3 with optional Jacobian.

Definition at line 36 of file Unit3.cpp.

Vector2 gtsam::Unit3::localCoordinates ( const Unit3 s) const

The local coordinates function.

Definition at line 277 of file Unit3.cpp.

Unit3& gtsam::Unit3::operator= ( const Unit3 u)
inline

Copy assignment.

Definition at line 91 of file Unit3.h.

Point3 gtsam::Unit3::point3 ( OptionalJacobian< 3, 2 >  H = boost::none) const

Return unit-norm Point3.

Definition at line 136 of file Unit3.cpp.

void gtsam::Unit3::print ( const std::string &  s = std::string()) const

The print fuction.

Definition at line 156 of file Unit3.cpp.

Unit3 gtsam::Unit3::Random ( std::mt19937 &  rng)
static

Random direction, using boost::uniform_on_sphere Example: std::mt19937 engine(42); Unit3 unit = Unit3::Random(engine);

Definition at line 47 of file Unit3.cpp.

Unit3 gtsam::Unit3::retract ( const Vector2 v,
OptionalJacobian< 2, 2 >  H = boost::none 
) const

The retract function.

Definition at line 247 of file Unit3.cpp.

template<class ARCHIVE >
void gtsam::Unit3::serialize ( ARCHIVE &  ar,
const unsigned  int 
)
inlineprivate

Definition at line 212 of file Unit3.h.

Matrix3 gtsam::Unit3::skew ( ) const

Return skew-symmetric associated with 3D point on unit sphere.

Definition at line 161 of file Unit3.cpp.

Vector3 gtsam::Unit3::unitVector ( OptionalJacobian< 3, 2 >  H = boost::none) const

Return unit-norm Vector.

Definition at line 143 of file Unit3.cpp.

Friends And Related Function Documentation

friend class boost::serialization::access
friend

Serialization function

Definition at line 210 of file Unit3.h.

Point3 operator* ( double  s,
const Unit3 d 
)
friend

Return scaled direction as Point3.

Definition at line 147 of file Unit3.h.

std::ostream& operator<< ( std::ostream &  os,
const Unit3 pair 
)
friend

Definition at line 150 of file Unit3.cpp.

Member Data Documentation

boost::optional<Matrix32> gtsam::Unit3::B_
mutableprivate

Cached basis.

Definition at line 47 of file Unit3.h.

boost::optional<Matrix62> gtsam::Unit3::H_B_
mutableprivate

Cached basis derivative.

Definition at line 48 of file Unit3.h.

Vector3 gtsam::Unit3::p_
private

The location of the point on the unit sphere.

Definition at line 46 of file Unit3.h.


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


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:58:37