21 #include <gtsam/config.h> 23 #ifndef GTSAM_USE_QUATERNIONS 27 #include <boost/math/constants/constants.hpp> 35 Rot3::Rot3() : rot_(I_3x3) {}
40 R << col1, col2, col3;
46 double R23,
double R31,
double R32,
double R33) {
48 R << R11,
R12, R13, R21, R22, R23, R31, R32, R33;
58 double st =
sin(t), ct =
cos(t);
67 double st =
sin(t), ct =
cos(t);
76 double st =
sin(t), ct =
cos(t);
89 double cz=
cos(z),sz=
sin(z);
100 double ssc = ss_ * cz,
csc = cs_ * cz, sss = ss_ * sz, css = cs_ * sz;
101 if (Hx) (*Hx) << 1, 0, 0;
102 if (Hy) (*Hy) << 0,
cx, -sx;
103 if (Hz) (*Hz) << -sy, sc_, cc_;
105 _cc,- c_s + ssc, s_s + csc,
106 _cs, c_c + sss, -s_c + css,
125 Vector3 x = rot.block<1, 3>(0, 0),
y = rot.block<1, 3>(1, 0);
128 Vector3 x_ort = x - (error / 2) *
y, y_ort =
y - (error / 2) *
x;
129 Vector3 z_ort = x_ort.cross(y_ort);
131 rot_orth.block<1, 3>(0, 0) = 0.5 * (3 - x_ort.dot(x_ort)) * x_ort;
132 rot_orth.block<1, 3>(1, 0) = 0.5 * (3 - y_ort.dot(y_ort)) * y_ort;
133 rot_orth.block<1, 3>(2, 0) = 0.5 * (3 - z_ort.dot(z_ort)) * z_ort;
135 return Rot3(rot_orth);
164 if (H)
throw std::runtime_error(
"Rot3::CayleyChart::Retract Derivative");
165 const double x = omega(0),
y = omega(1),
z = omega(2);
166 const double x2 = x *
x, y2 =
y *
y,
z2 =
z *
z;
167 const double xy = x *
y, xz = x *
z, yz = y *
z;
168 const double f = 1.0 / (4.0 + x2 + y2 +
z2), _2f = 2.0 * f;
169 return Rot3((4 + x2 - y2 - z2) * f, (xy - 2 * z) * _2f, (xz + 2 * y) * _2f,
170 (xy + 2 * z) * _2f, (4 - x2 + y2 - z2) * f, (yz - 2 * x) * _2f,
171 (xz - 2 * y) * _2f, (yz + 2 * x) * _2f, (4 - x2 - y2 + z2) * f);
176 if (H)
throw std::runtime_error(
"Rot3::CayleyChart::Local Derivative");
182 throw std::runtime_error(
"Rot3::CayleyChart::Local Invalid Rotation");
190 const double a = A(0, 0),
b = A(0, 1),
c = A(0, 2);
191 const double d = A(1, 0),
e = A(1, 1),
f = A(1, 2);
192 const double g = A(2, 0),
h = A(2, 1),
i = A(2, 2);
193 const double di = d *
i, ce =
c *
e, cd =
c *
d, fg =
f *
g;
194 const double M = 1 + e -
f *
h + i + e *
i;
195 const double K = -4.0 / (cd *
h + M + a * M - g * (
c + ce) -
b * (d + di - fg));
196 const double x = a *
f - cd +
f;
197 const double y =
b * f - ce -
c;
198 const double z = fg - di -
d;
207 else throw std::runtime_error(
"Rot3::Retract: unknown mode");
215 else throw std::runtime_error(
"Rot3::Local: unknown mode");
int EIGEN_BLAS_FUNC() rot(int *n, RealScalar *px, int *incx, RealScalar *py, int *incy, RealScalar *pc, RealScalar *ps)
Point3 r1() const
first column
Matrix< RealScalar, Dynamic, Dynamic > M
void determinant(const MatrixType &m)
Use the Lie group exponential map to retract.
Rot2 R(Rot2::fromAngle(0.1))
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
static Vector3 Local(const Rot3 &r, OptionalJacobian< 3, 3 > H=boost::none)
Pose3 x2(Rot3::Ypr(0.0, 0.0, 0.0), l2)
const MatrixNN & matrix() const
Return matrix.
static Rot3 RzRyRx(double x, double y, double z, OptionalJacobian< 3, 1 > Hx=boost::none, OptionalJacobian< 3, 1 > Hy=boost::none, OptionalJacobian< 3, 1 > Hz=boost::none)
Rotations around Z, Y, then X axes as in http://en.wikipedia.org/wiki/Rotation_matrix, counterclockwise when looking from unchanging axis.
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
Point3 rotate(const Point3 &p, OptionalJacobian< 3, 3 > H1=boost::none, OptionalJacobian< 3, 3 > H2=boost::none) const
3*3 matrix representation of SO(3)
static Vector3 Local(const Rot3 &r, ChartJacobian H=boost::none)
void g(const string &key, int i)
Retract and localCoordinates using the Cayley transform.
EIGEN_DEVICE_FUNC const CosReturnType cos() const
static Rot3 Rx(double t)
Rotation around X axis as in http://en.wikipedia.org/wiki/Rotation_matrix, counterclockwise when look...
static EIGEN_DEVICE_FUNC Matrix< Scalar, 2, 2 > toRotationMatrix(const Scalar &s)
Point3 r2() const
second column
Point3 r3() const
third column
static Rot3 Retract(const Vector3 &v, ChartJacobian H=boost::none)
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
EIGEN_DEVICE_FUNC const Scalar & q
static Rot3 Expmap(const Vector3 &v, OptionalJacobian< 3, 3 > H=boost::none)
#define ROT3_DEFAULT_COORDINATES_MODE
Matrix3 transpose() const
Matrix3 skewSymmetric(double wx, double wy, double wz)
static Vector3 Logmap(const Rot3 &R, OptionalJacobian< 3, 3 > H=boost::none)
static Rot3 Rz(double t)
Rotation around Z axis as in http://en.wikipedia.org/wiki/Rotation_matrix, counterclockwise when look...
The quaternion class used to represent 3D orientations and rotations.
static TangentVector Logmap(const SO &R, ChartJacobian H=boost::none)
EIGEN_DEVICE_FUNC const SinReturnType sin() const
const mpreal csc(const mpreal &x, mp_rnd_t r=mpreal::get_default_rnd())
Rot3 operator*(const Rot3 &R2) const
Syntatic sugar for composing two rotations.
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
static Rot3 Retract(const Vector3 &v, OptionalJacobian< 3, 3 > H=boost::none)
Q R2(Eigen::AngleAxisd(2, Vector3(0, 1, 0)))
gtsam::Quaternion toQuaternion() const
static Rot3 Ry(double t)
Rotation around Y axis as in http://en.wikipedia.org/wiki/Rotation_matrix, counterclockwise when look...
3D rotation represented as a rotation matrix or quaternion
Eigen::Quaternion< double, Eigen::DontAlign > Quaternion