Represents a 3D point on a unit sphere. More...
#include <Unit3.h>
Static Public Attributes | |
| constexpr static auto | 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... | |
| Unit3 & | operator= (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... | |
|
explicit |
| gtsam::Unit3::Unit3 | ( | double | x, |
| double | y, | ||
| double | z | ||
| ) |
|
explicit |
|
inline |
| const Matrix32 & gtsam::Unit3::basis | ( | OptionalJacobian< 6, 2 > | H = {} | ) | const |
|
inlinestatic |
|
inline |
| double gtsam::Unit3::distance | ( | const Unit3 & | q, |
| OptionalJacobian< 1, 2 > | H = {} |
||
| ) | const |
| double gtsam::Unit3::dot | ( | const Unit3 & | q, |
| OptionalJacobian< 1, 2 > | H1 = {}, |
||
| OptionalJacobian< 1, 2 > | H2 = {} |
||
| ) | const |
| Vector2 gtsam::Unit3::error | ( | const Unit3 & | q, |
| OptionalJacobian< 2, 2 > | H_q = {} |
||
| ) | const |
Signed, vector-valued error between two directions
| Vector2 gtsam::Unit3::errorVector | ( | const Unit3 & | q, |
| OptionalJacobian< 2, 2 > | H_p = {}, |
||
| OptionalJacobian< 2, 2 > | H_q = {} |
||
| ) | const |
|
static |
| Point3 gtsam::Unit3::point3 | ( | OptionalJacobian< 3, 2 > | H = {} | ) | const |
| void gtsam::Unit3::print | ( | const std::string & | s = std::string() | ) | const |
|
static |
| Unit3 gtsam::Unit3::retract | ( | const Vector2 & | v, |
| OptionalJacobian< 2, 2 > | H = {} |
||
| ) | const |
| Matrix3 gtsam::Unit3::skew | ( | ) | const |
| Vector3 gtsam::Unit3::unitVector | ( | OptionalJacobian< 3, 2 > | H = {} | ) | const |
|
friend |
|
mutableprivate |
|
inlinestaticconstexpr |
|
mutableprivate |
|
private |