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

std::optional< Matrix32 > B_
 Cached basis. More...
 
std::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 Unit3 FromPoint3 (const Point3 &point, OptionalJacobian< 2, 3 > H={})
 Named constructor from Point3 with optional Jacobian. More...
 
static Unit3 Random (std::mt19937 &rng)
 

Testable

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...
 
GTSAM_EXPORT friend std::ostream & operator<< (std::ostream &os, const Unit3 &pair)
 

Other functionality

const Matrix32 & basis (OptionalJacobian< 6, 2 > H={}) const
 
Matrix3 skew () const
 Return skew-symmetric associated with 3D point on unit sphere. More...
 
Point3 point3 (OptionalJacobian< 3, 2 > H={}) const
 Return unit-norm Point3. More...
 
Vector3 unitVector (OptionalJacobian< 3, 2 > H={}) const
 Return unit-norm Vector. More...
 
double dot (const Unit3 &q, OptionalJacobian< 1, 2 > H1={}, OptionalJacobian< 1, 2 > H2={}) const
 Return dot product with q. More...
 
Vector2 error (const Unit3 &q, OptionalJacobian< 2, 2 > H_q={}) const
 
Vector2 errorVector (const Unit3 &q, OptionalJacobian< 2, 2 > H_p={}, OptionalJacobian< 2, 2 > H_q={}) const
 
double distance (const Unit3 &q, OptionalJacobian< 1, 2 > H={}) 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...
 
Point3 operator* (double s, const Unit3 &d)
 Return scaled direction as Point3. More...
 

Manifold

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

Detailed Description

Represents a 3D point on a unit sphere.

Definition at line 42 of file Unit3.h.

Member Enumeration Documentation

◆ anonymous enum

anonymous enum
Enumerator
dimension 

Definition at line 56 of file Unit3.h.

◆ CoordinatesMode

Enumerator
EXPMAP 

Use the exponential map to retract.

RENORM 

Retract with vector addition and renormalize.

Definition at line 186 of file Unit3.h.

Constructor & Destructor Documentation

◆ Unit3() [1/5]

gtsam::Unit3::Unit3 ( )
inline

Default constructor.

Definition at line 64 of file Unit3.h.

◆ Unit3() [2/5]

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

Construct from point.

Definition at line 36 of file Unit3.cpp.

◆ Unit3() [3/5]

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

Construct from x,y,z.

Definition at line 38 of file Unit3.cpp.

◆ Unit3() [4/5]

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

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 40 of file Unit3.cpp.

◆ Unit3() [5/5]

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

Copy constructor.

Definition at line 79 of file Unit3.h.

Member Function Documentation

◆ basis()

const Matrix32 & gtsam::Unit3::basis ( OptionalJacobian< 6, 2 >  H = {}) 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 84 of file Unit3.cpp.

◆ cross() [1/2]

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

Cross-product w Point3.

Definition at line 167 of file Unit3.h.

◆ cross() [2/2]

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

Cross-product between two Unit3s.

Definition at line 162 of file Unit3.h.

◆ Dim()

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

Dimensionality of tangent space = 2 DOF.

Definition at line 177 of file Unit3.h.

◆ dim()

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

Dimensionality of tangent space = 2 DOF.

Definition at line 182 of file Unit3.h.

◆ distance()

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

Distance between two directions.

Definition at line 245 of file Unit3.cpp.

◆ dot()

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

Return dot product with q.

Definition at line 174 of file Unit3.cpp.

◆ equals()

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

The equals function with tolerance.

Definition at line 115 of file Unit3.h.

◆ error()

Vector2 gtsam::Unit3::error ( const Unit3 q,
OptionalJacobian< 2, 2 >  H_q = {} 
) const

Signed, vector-valued error between two directions

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

Definition at line 199 of file Unit3.cpp.

◆ errorVector()

Vector2 gtsam::Unit3::errorVector ( const Unit3 q,
OptionalJacobian< 2, 2 >  H_p = {},
OptionalJacobian< 2, 2 >  H_q = {} 
) 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 209 of file Unit3.cpp.

◆ FromPoint3()

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

Named constructor from Point3 with optional Jacobian.

Definition at line 44 of file Unit3.cpp.

◆ localCoordinates()

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

The local coordinates function.

Definition at line 285 of file Unit3.cpp.

◆ operator=()

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

Copy assignment.

Definition at line 84 of file Unit3.h.

◆ point3()

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

Return unit-norm Point3.

Definition at line 144 of file Unit3.cpp.

◆ print()

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

The print fuction.

Definition at line 164 of file Unit3.cpp.

◆ Random()

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 55 of file Unit3.cpp.

◆ retract()

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

The retract function.

Definition at line 255 of file Unit3.cpp.

◆ skew()

Matrix3 gtsam::Unit3::skew ( ) const

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

Definition at line 169 of file Unit3.cpp.

◆ unitVector()

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

Return unit-norm Vector.

Definition at line 151 of file Unit3.cpp.

Friends And Related Function Documentation

◆ operator*

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

Return scaled direction as Point3.

Definition at line 141 of file Unit3.h.

◆ operator<<

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

Definition at line 158 of file Unit3.cpp.

Member Data Documentation

◆ B_

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

Cached basis.

Definition at line 47 of file Unit3.h.

◆ H_B_

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

Cached basis derivative.

Definition at line 48 of file Unit3.h.

◆ p_

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 Thu Jun 13 2024 03:18:12