Go to the documentation of this file.
18 #include <gtsam/config.h>
20 #ifdef GTSAM_USE_QUATERNIONS
30 Rot3::Rot3() : quaternion_(
Quaternion::Identity()) {}
34 quaternion_((Matrix3() <<
35 col1.
x(), col2.
x(), col3.
x(),
36 col1.
y(), col2.
y(), col3.
y(),
37 col1.
z(), col2.
z(), col3.
z()).finished()) {}
41 double R21,
double R22,
double R23,
42 double R31,
double R32,
double R33) :
43 quaternion_((Matrix3() <<
46 R31, R32, R33).finished()) {}
69 Rot3
Rot3::RzRyRx(
double x,
double y,
double z, OptionalJacobian<3, 1> Hx,
70 OptionalJacobian<3, 1> Hy, OptionalJacobian<3, 1> Hz) {
71 if (Hx) (*Hx) << 1, 0, 0;
75 if (Hy) (*Hy) << 0,
cx, -sx;
78 (*Hz) << -sy, sx *
cy,
cx *
cy;
90 return Rot3(quaternion_.normalized());
94 return Rot3(quaternion_ *
R2.quaternion_);
106 return matrix().transpose();
111 OptionalJacobian<3,3> H1, OptionalJacobian<3,3> H2)
const {
116 return Point3(r.x(), r.y(), r.z());
121 return traits<gtsam::Quaternion>::Logmap(
R.quaternion_,
H);
128 else throw std::runtime_error(
"Rot3::Retract: unknown mode");
135 else throw std::runtime_error(
"Rot3::Local: unknown mode");
139 Matrix3
Rot3::matrix()
const {
return quaternion_.toRotationMatrix();}
Point3 r2() const
second column
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
Eigen::Quaternion< double, Eigen::DontAlign > Quaternion
static Rot3 Retract(const Vector3 &v, ChartJacobian H={})
Jet< T, N > sin(const Jet< T, N > &f)
OptionalJacobian< N, N > ChartJacobian
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
Rot3 operator*(const Rot3 &R2) const
Syntatic sugar for composing two rotations.
Represents a 3D rotation as a rotation angle around an arbitrary 3D axis.
Matrix3 skewSymmetric(double wx, double wy, double wz)
Point3 r3() const
third column
Jet< T, N > cos(const Jet< T, N > &f)
3D rotation represented as a rotation matrix or quaternion
static Vector3 Local(const Rot3 &r, ChartJacobian H={})
Point3 rotate(const Point3 &p, OptionalJacobian< 3, 3 > H1={}, OptionalJacobian< 3, 3 > H2={}) const
EIGEN_DEVICE_FUNC const Scalar & q
static const DiscreteKey mode(modeKey, 2)
gtsam::Quaternion toQuaternion() const
Point3 r1() const
first column
static Rot3 Ry(double t)
Rotation around Y axis as in http://en.wikipedia.org/wiki/Rotation_matrix, counterclockwise when look...
@ EXPMAP
Use the Lie group exponential map to retract.
static Rot3 Rx(double t)
Rotation around X axis as in http://en.wikipedia.org/wiki/Rotation_matrix, counterclockwise when look...
The quaternion class used to represent 3D orientations and rotations.
static Rot3 Expmap(const Vector3 &v, OptionalJacobian< 3, 3 > H={})
static Rot3 Rz(double t)
Rotation around Z axis as in http://en.wikipedia.org/wiki/Rotation_matrix, counterclockwise when look...
Matrix3 transpose() const
static Vector3 Logmap(const Rot3 &R, OptionalJacobian< 3, 3 > H={})
static Rot3 RzRyRx(double x, double y, double z, OptionalJacobian< 3, 1 > Hx={}, OptionalJacobian< 3, 1 > Hy={}, OptionalJacobian< 3, 1 > Hz={})
Rotations around Z, Y, then X axes as in http://en.wikipedia.org/wiki/Rotation_matrix,...
Rot2 R(Rot2::fromAngle(0.1))
#define ROT3_DEFAULT_COORDINATES_MODE
gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:04:01