27 #include <gtsam/dllexport.h> 29 #include <boost/optional.hpp> 30 #include <boost/serialization/nvp.hpp> 47 mutable boost::optional<Matrix32>
B_;
48 mutable boost::optional<Matrix62>
H_B_;
51 mutable std::mutex B_mutex_;
118 GTSAM_EXPORT
void print(
const std::string&
s = std::string())
const;
138 GTSAM_EXPORT Matrix3
skew()
const;
183 inline static size_t Dim() {
188 inline size_t dim()
const {
211 template<
class ARCHIVE>
213 ar & BOOST_SERIALIZATION_NVP(p_);
Vector3 p_
The location of the point on the unit sphere.
Both ManifoldTraits and Testable.
Unit3(const Unit3 &u)
Copy constructor.
GTSAM_EXPORT const Matrix32 & basis(OptionalJacobian< 6, 2 > H=boost::none) const
friend std::ostream & operator<<(std::ostream &os, const Unit3 &pair)
GTSAM_EXPORT Unit3 retract(const Vector2 &v, OptionalJacobian< 2, 2 > H=boost::none) const
The retract function.
GTSAM_EXPORT Vector2 localCoordinates(const Unit3 &s) const
The local coordinates function.
GTSAM_EXPORT Vector3 unitVector(OptionalJacobian< 3, 2 > H=boost::none) const
Return unit-norm Vector.
GTSAM_EXPORT double distance(const Unit3 &q, OptionalJacobian< 1, 2 > H=boost::none) const
Distance between two directions.
Unit3(const Point2 &p, double f)
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size set set xzeroaxis lt lw set x2zeroaxis lt lw set yzeroaxis lt lw set y2zeroaxis lt lw set tics in set ticslevel set tics set mxtics default set mytics default set mx2tics default set my2tics default set xtics border mirror norotate autofreq set ytics border mirror norotate autofreq set ztics border nomirror norotate autofreq set nox2tics set noy2tics set timestamp bottom norotate set rrange[*:*] noreverse nowriteback set trange[*:*] noreverse nowriteback set urange[*:*] noreverse nowriteback set vrange[*:*] noreverse nowriteback set xlabel matrix size set x2label set timefmt d m y n H
static GTSAM_EXPORT Unit3 Random(std::mt19937 &rng)
boost::optional< Matrix32 > B_
Cached basis.
Represents a 3D point on a unit sphere.
GTSAM_EXPORT Vector2 errorVector(const Unit3 &q, OptionalJacobian< 2, 2 > H_p=boost::none, OptionalJacobian< 2, 2 > H_q=boost::none) const
Base class and basic functions for Manifold types.
Unit3 & operator=(const Unit3 &u)
Copy assignment.
static size_t Dim()
Dimensionality of tangent space = 2 DOF.
Point3 cross(const Point3 &q) const
Cross-product w Point3.
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
friend Point3 operator*(double s, const Unit3 &d)
Return scaled direction as Point3.
EIGEN_DEVICE_FUNC const Scalar & q
Unit3()
Default constructor.
GTSAM_EXPORT Vector2 error(const Unit3 &q, OptionalJacobian< 2, 2 > H_q=boost::none) const
GTSAM_EXPORT Point3 point3(OptionalJacobian< 3, 2 > H=boost::none) const
Return unit-norm Point3.
bool equal_with_abs_tol(const Eigen::DenseBase< MATRIX > &A, const Eigen::DenseBase< MATRIX > &B, double tol=1e-9)
GTSAM_EXPORT void print(const std::string &s=std::string()) const
The print fuction.
Retract with vector addition and renormalize.
Unit3(double x, double y, double z)
Construct from x,y,z.
ofstream os("timeSchurFactors.csv")
Unit3 cross(const Unit3 &q) const
Cross-product between two Unit3s.
friend class boost::serialization::access
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.
Unit3(const Vector3 &p)
Construct from point.
Use the exponential map to retract.
static GTSAM_EXPORT Unit3 FromPoint3(const Point3 &point, OptionalJacobian< 2, 3 > H=boost::none)
Named constructor from Point3 with optional Jacobian.
size_t dim() const
Dimensionality of tangent space = 2 DOF.
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW
void serialize(ARCHIVE &ar, const unsigned int)
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy x
boost::optional< Matrix62 > H_B_
Cached basis derivative.
bool equals(const Unit3 &s, double tol=1e-9) const
The equals function with tolerance.
GTSAM_EXPORT Matrix3 skew() const
Return skew-symmetric associated with 3D point on unit sphere.