Go to the documentation of this file.
24 #include <Eigen/Eigenvalues>
55 Matrix4 SO4::Hat(
const Vector6&
xi) {
65 return Y -
Y.transpose();
71 Vector6 SO4::Vee(
const Matrix4&
X) {
90 if (
H)
throw std::runtime_error(
"SO4::Expmap Jacobian");
93 const Matrix4
X = Hat(
xi);
97 Eigen::Vector4cd
e =
eig.eigenvalues();
100 return abs(a.imag()) > abs(b.imag());
104 double a =
e[0].imag(),
b =
e[2].imag();
105 if (!
e.real().isZero() ||
e[1].imag() != -
a ||
e[3].imag() != -
b) {
106 throw runtime_error(
"SO4::Expmap: wrong eigenvalues.");
113 const auto X2 =
X *
X;
114 const auto X3 =
X2 *
X;
116 if (
a != 0 &&
b == 0) {
119 }
else if (
a ==
b &&
b != 0) {
120 double sin_a =
sin(
a), cos_a =
cos(
a);
121 double c0 = (
a * sin_a + 2 * cos_a) / 2,
122 c1 = (3 * sin_a -
a * cos_a) / (2 *
a),
c2 = sin_a / (2 *
a),
123 c3 = (sin_a -
a * cos_a) / (2 *
a3);
126 double sin_a =
sin(
a), cos_a =
cos(
a);
127 double sin_b =
sin(
b), cos_b =
cos(
b);
128 double c0 = (
b2 * cos_a -
a2 * cos_b) / (
b2 -
a2),
130 c2 = (cos_a - cos_b) / (
b2 -
a2),
131 c3 = (
b * sin_a -
a * sin_b) / (
a *
b * (
b2 -
a2));
145 static std::vector<Matrix4, Eigen::aligned_allocator<Matrix4> >
G4(
146 {SO4::Hat(Vector6::Unit(0)), SO4::Hat(Vector6::Unit(1)),
147 SO4::Hat(Vector6::Unit(2)), SO4::Hat(Vector6::Unit(3)),
148 SO4::Hat(Vector6::Unit(4)), SO4::Hat(Vector6::Unit(5))});
159 Matrix6 SO4::AdjointMap()
const {
162 const Matrix4&
Q = matrix_;
163 const Matrix4 Qt =
Q.transpose();
165 for (
size_t i = 0;
i < 6;
i++) {
167 A.col(
i) = SO4::Vee(
Q *
G4[
i] * Qt);
179 *
H <<
Q *
P4.block<4, 6>(0, 0),
Q *
P4.block<4, 6>(4, 0),
180 Q *
P4.block<4, 6>(8, 0),
Q *
P4.block<4, 6>(12, 0);
188 SO4 SO4::ChartAtOrigin::Retract(
const Vector6&
xi, ChartJacobian
H) {
189 if (
H)
throw std::runtime_error(
"SO4::ChartAtOrigin::Retract Jacobian");
191 const Matrix4
X = Hat(
xi / 2);
198 Vector6 SO4::ChartAtOrigin::Local(
const SO4&
Q, ChartJacobian
H) {
199 if (
H)
throw std::runtime_error(
"SO4::ChartAtOrigin::Retract Jacobian");
200 const Matrix4&
R =
Q.matrix();
201 const Matrix4
X = (I_4x4 -
R) * (I_4x4 +
R).inverse();
207 const Matrix4&
R =
Q.matrix();
208 const Matrix3
M =
R.topLeftCorner<3, 3>();
211 q =
R.topRightCorner<3, 1>();
221 const Matrix4&
R =
Q.matrix();
222 const Matrix43
M =
R.leftCols<3>();
224 const auto &
m1 =
R.col(0),
m2 =
R.col(1),
m3 =
R.col(2),
q =
R.col(3);
225 *
H << Z_4x1, Z_4x1, -
q, Z_4x1, -
m3,
m2,
226 Z_4x1,
q, Z_4x1,
m3, Z_4x1, -
m1,
227 -
q, Z_4x1, Z_4x1, -
m2,
m1, Z_4x1;
GTSAM_EXPORT Matrix3 topLeft(const SO4 &Q, OptionalJacobian< 9, 6 > H)
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
const EIGEN_DEVICE_FUNC InverseReturnType inverse() const
Array< double, 1, 3 > e(1./3., 0.5, 2.)
GTSAM_EXPORT Matrix43 stiefel(const SO4 &Q, OptionalJacobian< 12, 6 > H)
Jet< T, N > sin(const Jet< T, N > &f)
static const Eigen::MatrixBase< Vector3 >::ConstantReturnType Z_3x1
GaussianFactorGraphValuePair Y
4*4 matrix representation of SO(4)
Jet< T, N > cos(const Jet< T, N > &f)
Matrix< SCALARA, Dynamic, Dynamic, opt_A > A
Pose2_ Expmap(const Vector3_ &xi)
EIGEN_DEVICE_FUNC const Scalar & q
static SO4::VectorN2 vec4(const Matrix4 &Q)
SelfAdjointEigenSolver< PlainMatrixType > eig(mat, computeVectors?ComputeEigenvectors:EigenvaluesOnly)
A matrix or vector expression mapping an existing array of data.
static const DiscreteKey m3(M(3), 2)
The quaternion class used to represent 3D orientations and rotations.
Computes eigenvalues and eigenvectors of general matrices.
The matrix class, also used for vectors and row-vectors.
static std::vector< Matrix4, Eigen::aligned_allocator< Matrix4 > > G4({SO4::Hat(Vector6::Unit(0)), SO4::Hat(Vector6::Unit(1)), SO4::Hat(Vector6::Unit(2)), SO4::Hat(Vector6::Unit(3)), SO4::Hat(Vector6::Unit(4)), SO4::Hat(Vector6::Unit(5))})
Rot2 R(Rot2::fromAngle(0.1))
Matrix< RealScalar, Dynamic, Dynamic > M
gtsam
Author(s):
autogenerated on Fri Nov 1 2024 03:35:31