Go to the documentation of this file.
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
61 #ifdef GTSAM_USE_QUATERNIONS
84 Rot3(
double R11,
double R12,
double R13,
85 double R21,
double R22,
double R23,
86 double R31,
double R32,
double R33);
95 template <
typename Derived>
96 #ifdef GTSAM_USE_QUATERNIONS
98 quaternion_ = Matrix3(
R);
109 #ifdef GTSAM_USE_QUATERNIONS
110 explicit Rot3(
const Matrix3&
R) : quaternion_(
R) {}
112 explicit Rot3(
const Matrix3&
R) : rot_(
R) {}
118 #ifdef GTSAM_USE_QUATERNIONS
137 static Rot3 Random(std::mt19937 &
rng);
145 static Rot3 Rx(
double t);
148 static Rot3 Ry(
double t);
151 static Rot3 Rz(
double t);
154 static Rot3 RzRyRx(
double x,
double y,
double z,
156 OptionalJacobian<3, 1> Hy = {},
157 OptionalJacobian<3, 1> Hz = {});
162 assert(xyz.size() == 3);
166 out = RzRyRx(xyz(0), xyz(1), xyz(2), Hx, Hy, Hz);
169 out = RzRyRx(xyz(0), xyz(1), xyz(2));
199 OptionalJacobian<3, 1> Hr = {}) {
200 return RzRyRx(r,
p,
y, Hr, Hp, Hy);
218 #ifdef GTSAM_USE_QUATERNIONS
252 return Rodrigues(
Vector3(wx, wy, wz));
283 Rot3 normalized()
const;
290 void print(
const std::string&
s=
"")
const;
309 #ifdef GTSAM_USE_QUATERNIONS
310 return Rot3(quaternion_.inverse());
341 #ifndef GTSAM_USE_QUATERNIONS
346 #ifndef GTSAM_USE_QUATERNIONS
376 #ifdef GTSAM_USE_QUATERNIONS
387 static Vector3 Logmap(
const Rot3&
R, OptionalJacobian<3,3>
H = {});
390 static Matrix3 ExpmapDerivative(
const Vector3&
x);
393 static Matrix3 LogmapDerivative(
const Vector3&
x);
421 OptionalJacobian<3,3> H2={})
const;
428 Unit3
rotate(
const Unit3&
p, OptionalJacobian<2,3>
HR = {},
429 OptionalJacobian<2,2> Hp = {})
const;
432 Unit3
unrotate(
const Unit3&
p, OptionalJacobian<2,3>
HR = {},
433 OptionalJacobian<2,2> Hp = {})
const;
448 Matrix3 transpose()
const;
461 Vector3 xyz(OptionalJacobian<3, 3>
H = {})
const;
467 Vector3 ypr(OptionalJacobian<3, 3>
H = {})
const;
473 Vector3 rpy(OptionalJacobian<3, 3>
H = {})
const;
481 double roll(OptionalJacobian<1, 3>
H = {})
const;
489 double pitch(OptionalJacobian<1, 3>
H = {})
const;
497 double yaw(OptionalJacobian<1, 3>
H = {})
const;
511 std::pair<Unit3, double> axisAngle()
const;
523 Rot3 slerp(
double t,
const Rot3&
other)
const;
526 GTSAM_EXPORT
friend std::ostream &
operator<<(std::ostream &
os,
const Rot3&
p);
531 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
533 friend class boost::serialization::access;
534 template <
class ARCHIVE>
535 void serialize(ARCHIVE& ar,
const unsigned int ) {
536 #ifndef GTSAM_USE_QUATERNIONS
538 ar& boost::serialization::make_nvp(
"rot11",
M(0, 0));
539 ar& boost::serialization::make_nvp(
"rot12",
M(0, 1));
540 ar& boost::serialization::make_nvp(
"rot13",
M(0, 2));
541 ar& boost::serialization::make_nvp(
"rot21",
M(1, 0));
542 ar& boost::serialization::make_nvp(
"rot22",
M(1, 1));
543 ar& boost::serialization::make_nvp(
"rot23",
M(1, 2));
544 ar& boost::serialization::make_nvp(
"rot31",
M(2, 0));
545 ar& boost::serialization::make_nvp(
"rot32",
M(2, 1));
546 ar& boost::serialization::make_nvp(
"rot33",
M(2, 2));
548 ar& boost::serialization::make_nvp(
"w", quaternion_.w());
549 ar& boost::serialization::make_nvp(
"x", quaternion_.x());
550 ar& boost::serialization::make_nvp(
"y", quaternion_.y());
551 ar& boost::serialization::make_nvp(
"z", quaternion_.z());
556 #ifdef GTSAM_USE_QUATERNIONS
564 using Rot3Vector = std::vector<Rot3, Eigen::aligned_allocator<Rot3>>;
576 GTSAM_EXPORT std::pair<Matrix3, Vector3>
RQ(
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 SO AxisAngle(const Vector3 &axis, double theta)
Constructor from axis and angle. Only defined for SO3.
Eigen::Quaternion< double, Eigen::DontAlign > Quaternion
static Rot3 RzRyRx(const Vector &xyz, OptionalJacobian< 3, 3 > H={})
Rotations around Z, Y, then X axes as in http://en.wikipedia.org/wiki/Rotation_matrix,...
const MATRIX::ConstColXpr column(const MATRIX &A, size_t j)
Expression< T > between(const Expression< T > &t1, const Expression< T > &t2)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
std::ostream & operator<<(std::ostream &os, const Dih6 &m)
static Rot3 Rodrigues(double wx, double wy, double wz)
static Rot3 Quaternion(double w, double x, double y, double z)
static Rot3 Identity()
identity rotation for group operation
static Rot3 ClosestTo(const Matrix3 &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
Represents a 3D rotation as a rotation angle around an arbitrary 3D axis.
static Rot3 Yaw(double t)
Positive yaw is to right (as in aircraft heading). See ypr.
ofstream os("timeSchurFactors.csv")
Rot3 retractCayley(const Vector &omega) const
Retraction from R^3 to Rot3 manifold using the Cayley transform.
static Rot3 Ypr(double y, double p, double r, OptionalJacobian< 3, 1 > Hy={}, OptionalJacobian< 3, 1 > Hp={}, OptionalJacobian< 3, 1 > Hr={})
static Rot3 Roll(double t)
Point2 operator*(double s, const Point2 &p)
multiply with scalar
MatrixNN matrix_
Rotation matrix.
Expression< T > compose(const Expression< T > &t1, const Expression< T > &t2)
3*3 matrix representation of SO(3)
Pose2_ Expmap(const Vector3_ &xi)
void print(const Matrix &A, const string &s, ostream &stream)
Point3_ unrotate(const Rot3_ &x, const Point3_ &p)
Point3_ rotate(const Rot3_ &x, const Point3_ &p)
EIGEN_DEVICE_FUNC const Scalar & q
const MatrixNN & matrix() const
Return matrix.
Both LieGroupTraits and Testable.
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
static Rot3 Rodrigues(const Vector3 &w)
Rot3 conjugate(const Rot3 &cRb) const
std::vector< Rot3, Eigen::aligned_allocator< Rot3 > > Rot3Vector
std::vector of Rot3s, used in Matlab wrapper
Matrix3 AdjointMap() const
static Rot3 Pitch(double t)
Positive pitch is up (increasing aircraft altitude).See ypr.
Rot3 inverse() const
inverse of a rotation
std::ofstream out("Result.txt")
static Rot3 AxisAngle(const Unit3 &axis, double angle)
@ EXPMAP
Use the Lie group exponential map to retract.
Map< Matrix< T, Dynamic, Dynamic, ColMajor >, 0, OuterStride<> > matrix(T *data, int rows, int cols, int stride)
Vector3 localCayley(const Rot3 &other) const
Inverse of retractCayley.
The quaternion class used to represent 3D orientations and rotations.
static Matrix3 ExpmapDerivative(const Vector3 &x)
Derivative of Expmap.
Lie Group wrapper for Eigen Quaternions.
static Rot3 Expmap(const Vector3 &v, OptionalJacobian< 3, 3 > H={})
Rot3(const Eigen::MatrixBase< Derived > &R)
Array< int, Dynamic, 1 > v
static SO ClosestTo(const MatrixNN &M)
Base class for all dense matrices, vectors, and expressions.
Represents a 3D point on a unit sphere.
Vector3 unitVector(OptionalJacobian< 3, 2 > H={}) const
Return unit-norm Vector.
@ CAYLEY
Retract and localCoordinates using the Cayley transform.
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW
Rot2 R(Rot2::fromAngle(0.1))
pair< Matrix3, Vector3 > RQ(const Matrix3 &A, OptionalJacobian< 3, 9 > H)
static Rot3 AxisAngle(const Point3 &axis, double angle)
Rot3(double w, double x, double y, double z)
Matrix< RealScalar, Dynamic, Dynamic > M
gtsam
Author(s):
autogenerated on Fri Nov 1 2024 03:35:00