30 #include <gtsam/config.h> 35 #ifndef ROT3_DEFAULT_COORDINATES_MODE 36 #ifdef GTSAM_USE_QUATERNIONS 38 #define ROT3_DEFAULT_COORDINATES_MODE Rot3::EXPMAP 41 #ifndef GTSAM_ROT3_EXPMAP 43 #define ROT3_DEFAULT_COORDINATES_MODE Rot3::CAYLEY 45 #define ROT3_DEFAULT_COORDINATES_MODE Rot3::EXPMAP 63 #ifdef GTSAM_USE_QUATERNIONS 87 Rot3(
double R11,
double R12,
double R13,
88 double R21,
double R22,
double R23,
89 double R31,
double R32,
double R33);
98 template <
typename Derived>
99 #ifdef GTSAM_USE_QUATERNIONS 101 quaternion_ = Matrix3(R);
112 #ifdef GTSAM_USE_QUATERNIONS 113 explicit Rot3(
const Matrix3&
R) : quaternion_(R) {}
115 explicit Rot3(
const Matrix3& R) : rot_(R) {}
121 #ifdef GTSAM_USE_QUATERNIONS 140 static Rot3 Random(std::mt19937 &
rng);
148 static Rot3 Rx(
double t);
151 static Rot3 Ry(
double t);
154 static Rot3 Rz(
double t);
157 static Rot3 RzRyRx(
double x,
double y,
double z,
165 assert(xyz.size() == 3);
169 out = RzRyRx(xyz(0), xyz(1), xyz(2), Hx, Hy, Hz);
172 out = RzRyRx(xyz(0), xyz(1), xyz(2));
203 return RzRyRx(r, p, y, Hr, Hp, Hy);
221 #ifdef GTSAM_USE_QUATERNIONS 255 return Rodrigues(
Vector3(wx, wy, wz));
286 Rot3 normalized()
const;
293 void print(
const std::string&
s=
"")
const;
312 #ifdef GTSAM_USE_QUATERNIONS 326 return cRb * (*this) * cRb.
inverse();
344 #ifndef GTSAM_USE_QUATERNIONS 349 #ifndef GTSAM_USE_QUATERNIONS 359 return compose(CayleyChart::Retract(omega));
364 return CayleyChart::Local(
between(other));
379 #ifdef GTSAM_USE_QUATERNIONS 393 static Matrix3 ExpmapDerivative(
const Vector3& x);
396 static Matrix3 LogmapDerivative(
const Vector3& x);
451 Matrix3 transpose()
const;
514 std::pair<Unit3, double> axisAngle()
const;
532 Rot3 slerp(
double t,
const Rot3& other)
const;
535 GTSAM_EXPORT
friend std::ostream &
operator<<(std::ostream &
os,
const Rot3& p);
541 friend class boost::serialization::access;
542 template <
class ARCHIVE>
544 #ifndef GTSAM_USE_QUATERNIONS 546 ar& boost::serialization::make_nvp(
"rot11",
M(0, 0));
547 ar& boost::serialization::make_nvp(
"rot12",
M(0, 1));
548 ar& boost::serialization::make_nvp(
"rot13",
M(0, 2));
549 ar& boost::serialization::make_nvp(
"rot21",
M(1, 0));
550 ar& boost::serialization::make_nvp(
"rot22",
M(1, 1));
551 ar& boost::serialization::make_nvp(
"rot23",
M(1, 2));
552 ar& boost::serialization::make_nvp(
"rot31",
M(2, 0));
553 ar& boost::serialization::make_nvp(
"rot32",
M(2, 1));
554 ar& boost::serialization::make_nvp(
"rot33",
M(2, 2));
556 ar& boost::serialization::make_nvp(
"w", quaternion_.
w());
557 ar& boost::serialization::make_nvp(
"x", quaternion_.
x());
558 ar& boost::serialization::make_nvp(
"y", quaternion_.
y());
559 ar& boost::serialization::make_nvp(
"z", quaternion_.
z());
563 #ifdef GTSAM_USE_QUATERNIONS 580 GTSAM_EXPORT std::pair<Matrix3, Vector3>
RQ(
Point3_ unrotate(const Rot3_ &x, const Point3_ &p)
void print(const Matrix &A, const string &s, ostream &stream)
void serialize(ARCHIVE &ar, const unsigned int)
Matrix< RealScalar, Dynamic, Dynamic > M
std::ostream & operator<<(std::ostream &os, const Dih6 &m)
EIGEN_DEVICE_FUNC CoeffReturnType x() const
Rot3(const Eigen::MatrixBase< Derived > &R)
static SO AxisAngle(const Vector3 &axis, double theta)
Constructor from axis and angle. Only defined for SO3.
EIGEN_DEVICE_FUNC CoeffReturnType y() const
static Rot3 Pitch(double t)
Positive pitch is up (increasing aircraft altitude).See ypr.
Use the Lie group exponential map to retract.
Rot2 R(Rot2::fromAngle(0.1))
Pose2_ Expmap(const Vector3_ &xi)
GTSAM_EXPORT Vector3 unitVector(OptionalJacobian< 3, 2 > H=boost::none) const
Return unit-norm Vector.
Rot3 conjugate(const Rot3 &cRb) const
Vector3 localCayley(const Rot3 &other) const
Inverse of retractCayley.
const MatrixNN & matrix() const
Return matrix.
Rot3 retractCayley(const Vector &omega) const
Retraction from R^3 to Rot3 manifold using the Cayley transform.
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
Matrix3 AdjointMap() const
3*3 matrix representation of SO(3)
Point2 operator*(double s, const Point2 &p)
multiply with scalar
Rot3(double w, double x, double y, double z)
static Rot3 Ypr(double y, double p, double r, OptionalJacobian< 3, 1 > Hy=boost::none, OptionalJacobian< 3, 1 > Hp=boost::none, OptionalJacobian< 3, 1 > Hr=boost::none)
Rot3 inverse() const
inverse of a rotation
EIGEN_DEVICE_FUNC Quaternion< Scalar > inverse() const
EIGEN_DEVICE_FUNC CoeffReturnType w() const
EIGEN_DEVICE_FUNC CoeffReturnType z() const
Retract and localCoordinates using the Cayley transform.
static Rot3 AxisAngle(const Unit3 &axis, double angle)
static Rot3 identity()
identity rotation for group operation
static Rot3 Quaternion(double w, double x, double y, double z)
MatrixNN matrix_
Rotation matrix.
Represents a 3D point on a unit sphere.
pair< Matrix3, Vector3 > RQ(const Matrix3 &A, OptionalJacobian< 3, 9 > H)
static Rot3 Rodrigues(const Vector3 &w)
static Rot3 Yaw(double t)
Positive yaw is to right (as in aircraft heading). See ypr.
static Rot3 Roll(double t)
static Matrix3 ExpmapDerivative(const Vector3 &x)
Derivative of Expmap.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
EIGEN_DEVICE_FUNC const Scalar & q
Point3_ rotate(const Rot3_ &x, const Point3_ &p)
static Rot3 Expmap(const Vector3 &v, OptionalJacobian< 3, 3 > H=boost::none)
static Rot3 AxisAngle(const Point3 &axis, double angle)
ofstream os("timeSchurFactors.csv")
Both LieGroupTraits and Testable.
The quaternion class used to represent 3D orientations and rotations.
Expression< T > compose(const Expression< T > &t1, const Expression< T > &t2)
static Rot3 ClosestTo(const Matrix3 &M)
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW
Map< Matrix< T, Dynamic, Dynamic, ColMajor >, 0, OuterStride<> > matrix(T *data, int rows, int cols, int stride)
static Rot3 Rodrigues(double wx, double wy, double wz)
static SO ClosestTo(const MatrixNN &M)
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
const MATRIX::ConstColXpr column(const MATRIX &A, size_t j)
Base class for all dense matrices, vectors, and expressions.
Q R2(Eigen::AngleAxisd(2, Vector3(0, 1, 0)))
Expression< T > between(const Expression< T > &t1, const Expression< T > &t2)
Represents a 3D rotation as a rotation angle around an arbitrary 3D axis.
static Rot3 RzRyRx(const Vector &xyz, OptionalJacobian< 3, 3 > H=boost::none)
Rotations around Z, Y, then X axes as in http://en.wikipedia.org/wiki/Rotation_matrix, counterclockwise when looking from unchanging axis.
Eigen::Quaternion< double, Eigen::DontAlign > Quaternion