Go to the documentation of this file.
38 H << I_3x3 *
R(0, 0), I_3x3 *
R(1, 0), I_3x3 *
R(2, 0),
39 I_3x3 *
R(0, 1), I_3x3 *
R(1, 1), I_3x3 *
R(2, 1),
40 I_3x3 *
R(0, 2), I_3x3 *
R(1, 2), I_3x3 *
R(2, 2);
45 Matrix3 MR =
M *
R.matrix();
63 W << 0.0, -wz, +wy, +wz, 0.0, -wx, -wy, +wx, 0.0;
73 : theta2(angle * angle), theta(angle) {
74 const double ax = axis.x(), ay = axis.y(), az = axis.z();
75 K << 0.0, -az, +ay, +az, 0.0, -ax, -ay, +ax, 0.0;
85 return SO3(I_3x3 +
W);
111 *H1 = (Db *
K - Da * I_3x3) * Kv *
omega.transpose() -
122 const Matrix3 invDexp =
dexp_.inverse();
125 Matrix3 D_dexpv_omega;
127 *H1 = -invDexp * D_dexpv_omega;
129 if (H2) *H2 = invDexp;
145 SO3 SO3::ClosestTo(
const Matrix3&
M) {
147 const auto&
U =
svd.matrixU();
148 const auto&
V =
svd.matrixV();
150 return SO3(
U *
Vector3(1, 1, det).asDiagonal() *
V.transpose());
156 SO3 SO3::ChordalMean(
const std::vector<SO3>& rotations) {
161 for (
const auto& R_i : rotations) {
164 return ClosestTo(C_e);
176 return Y -
Y.transpose();
182 Vector3 SO3::Vee(
const Matrix3&
X) {
193 Matrix3 SO3::AdjointMap()
const {
202 so3::DexpFunctor impl(
omega);
204 return impl.expmap();
206 return so3::ExpmapFunctor(
omega).expmap();
213 return so3::DexpFunctor(
omega).dexp();
238 const Matrix3
W = Hat(
omega);
239 return I_3x3 + 0.5 *
W +
240 (1 / (theta * theta) - (1 +
cos(theta)) / (2 * theta *
sin(theta))) *
252 const Matrix3&
R =
Q.matrix();
253 const double &R11 =
R(0, 0),
R12 =
R(0, 1), R13 =
R(0, 2);
254 const double &R21 =
R(1, 0), R22 =
R(1, 1), R23 =
R(1, 2);
255 const double &R31 =
R(2, 0), R32 =
R(2, 1), R33 =
R(2, 2);
258 const double tr =
R.trace();
264 if (tr + 1.0 < 1
e-3) {
265 if (R33 > R22 && R33 > R11) {
267 const double W = R21 -
R12;
268 const double Q1 = 2.0 + 2.0 * R33;
269 const double Q2 = R31 + R13;
270 const double Q3 = R23 + R32;
271 const double r =
sqrt(
Q1);
272 const double one_over_r = 1 / r;
274 const double sgn_w =
W < 0 ? -1.0 : 1.0;
275 const double mag =
M_PI - (2 * sgn_w *
W) / norm;
276 const double scale = 0.5 * one_over_r * mag;
278 }
else if (R22 > R11) {
280 const double W = R13 - R31;
281 const double Q1 = 2.0 + 2.0 * R22;
282 const double Q2 = R23 + R32;
283 const double Q3 =
R12 + R21;
284 const double r =
sqrt(
Q1);
285 const double one_over_r = 1 / r;
287 const double sgn_w =
W < 0 ? -1.0 : 1.0;
288 const double mag =
M_PI - (2 * sgn_w *
W) / norm;
289 const double scale = 0.5 * one_over_r * mag;
293 const double W = R32 - R23;
294 const double Q1 = 2.0 + 2.0 * R11;
295 const double Q2 =
R12 + R21;
296 const double Q3 = R31 + R13;
297 const double r =
sqrt(
Q1);
298 const double one_over_r = 1 / r;
300 const double sgn_w =
W < 0 ? -1.0 : 1.0;
301 const double mag =
M_PI - (2 * sgn_w *
W) / norm;
302 const double scale = 0.5 * one_over_r * mag;
307 const double tr_3 = tr - 3.0;
310 double theta =
acos((tr - 1.0) / 2.0);
311 magnitude = theta / (2.0 *
sin(theta));
316 magnitude = 0.5 - tr_3 / 12.0 + tr_3*tr_3/60.0;
321 if (
H) *
H = LogmapDerivative(
omega);
336 Vector3 SO3::ChartAtOrigin::Local(
const SO3&
R, ChartJacobian
H) {
342 static Vector9
vec3(
const Matrix3&
R) {
347 static std::vector<Matrix3>
G3({SO3::Hat(Vector3::Unit(0)),
348 SO3::Hat(Vector3::Unit(1)),
349 SO3::Hat(Vector3::Unit(2))});
359 const Matrix3&
R = matrix_;
362 *
H <<
R *
P3.block<3, 3>(0, 0),
R *
P3.block<3, 3>(3, 0),
363 R *
P3.block<3, 3>(6, 0);
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.
GTSAM_EXPORT Vector3 applyInvDexp(const Vector3 &v, OptionalJacobian< 3, 3 > H1={}, OptionalJacobian< 3, 3 > H2={}) const
Multiplies with dexp().inverse(), with optional derivatives.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
ExpmapFunctor(const Vector3 &omega, bool nearZeroApprox=false)
Constructor with element of Lie algebra so(3)
Jet< T, N > sin(const Jet< T, N > &f)
GaussianFactorGraphValuePair Y
GTSAM_EXPORT DexpFunctor(const Vector3 &omega, bool nearZeroApprox=false)
Constructor with element of Lie algebra so(3)
static Vector9 vec3(const Matrix3 &R)
Matrix3 skewSymmetric(double wx, double wy, double wz)
cout<< "Here is the matrix m:"<< endl<< m<< endl;JacobiSVD< MatrixXf > svd(m, ComputeThinU|ComputeThinV)
Jet< T, N > acos(const Jet< T, N > &f)
void determinant(const MatrixType &m)
Jet< T, N > cos(const Jet< T, N > &f)
3*3 matrix representation of SO(3)
Pose2_ Expmap(const Vector3_ &xi)
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 scale
const MatrixNN & matrix() const
Return matrix.
GTSAM_EXPORT Vector3 applyDexp(const Vector3 &v, OptionalJacobian< 3, 3 > H1={}, OptionalJacobian< 3, 3 > H2={}) const
Multiplies with dexp(), with optional derivatives.
void init(bool nearZeroApprox=false)
double dot(const V1 &a, const V2 &b)
Functor implementing Exponential map.
static std::vector< Matrix3 > G3({SO3::Hat(Vector3::Unit(0)), SO3::Hat(Vector3::Unit(1)), SO3::Hat(Vector3::Unit(2))})
A matrix or vector expression mapping an existing array of data.
Two-sided Jacobi SVD decomposition of a rectangular matrix.
The quaternion class used to represent 3D orientations and rotations.
GTSAM_EXPORT Matrix99 Dcompose(const SO3 &Q)
(constant) Jacobian of compose wrpt M
Array< int, Dynamic, 1 > v
SO3 expmap() const
Rodrigues formula.
Jet< T, N > sqrt(const Jet< T, N > &f)
Eigen::Matrix< double, 9, 3 > Matrix93
Rot2 R(Rot2::fromAngle(0.1))
GTSAM_EXPORT Matrix3 compose(const Matrix3 &M, const SO3 &R, OptionalJacobian< 9, 9 > H)
Matrix< RealScalar, Dynamic, Dynamic > M
gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:04:23