diff --git a/gtsam/geometry/Pose3.cpp b/gtsam/geometry/Pose3.cpp index 2e0463ceb..cc3282866 100644 --- a/gtsam/geometry/Pose3.cpp +++ b/gtsam/geometry/Pose3.cpp @@ -219,8 +219,7 @@ Pose3 Pose3::Expmap(const Vector6& xi, OptionalJacobian<6, 6> Hxi) { const Vector3 w = xi.head<3>(), v = xi.tail<3>(); // Instantiate functor for Dexp-related operations: - const bool nearZero = (w.dot(w) <= 1e-5); - const so3::DexpFunctor local(w, nearZero); + const so3::DexpFunctor local(w); // Compute rotation using Expmap #ifdef GTSAM_USE_QUATERNIONS @@ -256,25 +255,17 @@ Pose3 Pose3::Expmap(const Vector6& xi, OptionalJacobian<6, 6> Hxi) { /* ************************************************************************* */ Vector6 Pose3::Logmap(const Pose3& pose, OptionalJacobian<6, 6> Hpose) { - if (Hpose) *Hpose = LogmapDerivative(pose); const Vector3 w = Rot3::Logmap(pose.rotation()); - const Vector3 T = pose.translation(); - const double t = w.norm(); - if (t < 1e-10) { - Vector6 log; - log << w, T; - return log; - } else { - const Matrix3 W = skewSymmetric(w / t); - // Formula from Agrawal06iros, equation (14) - // simplified with Mathematica, and multiplying in T to avoid matrix math - const double Tan = tan(0.5 * t); - const Vector3 WT = W * T; - const Vector3 u = T - (0.5 * t) * WT + (1 - t / (2. * Tan)) * (W * WT); - Vector6 log; - log << w, u; - return log; - } + + // Instantiate functor for Dexp-related operations: + const so3::DexpFunctor local(w); + + const Vector3 t = pose.translation(); + const Vector3 u = local.applyLeftJacobianInverse(t); + Vector6 xi; + xi << w, u; + if (Hpose) *Hpose = LogmapDerivative(xi); + return xi; } /* ************************************************************************* */ @@ -309,25 +300,6 @@ Vector6 Pose3::ChartAtOrigin::Local(const Pose3& pose, ChartJacobian Hpose) { #endif } -/* ************************************************************************* */ -Matrix3 Pose3::ComputeQforExpmapDerivative(const Vector6& xi, - double nearZeroThreshold) { - const auto w = xi.head<3>(); - const auto v = xi.tail<3>(); - - // Instantiate functor for Dexp-related operations: - bool nearZero = (w.dot(w) <= nearZeroThreshold); - so3::DexpFunctor local(w, nearZero); - - // Call applyLeftJacobian to get its Jacobian - Matrix3 H; - local.applyLeftJacobian(v, H); - - // Multiply with R^T to account for the Pose3::Create Jacobian. - const Matrix3 R = local.expmap(); - return R.transpose() * H; -} - /* ************************************************************************* */ Matrix6 Pose3::ExpmapDerivative(const Vector6& xi) { Matrix6 J; @@ -335,16 +307,35 @@ Matrix6 Pose3::ExpmapDerivative(const Vector6& xi) { return J; } +/* ************************************************************************* */ +Matrix6 Pose3::LogmapDerivative(const Vector6& xi) { + const Vector3 w = xi.head<3>(); + Vector3 v = xi.segment<3>(3); + + // Instantiate functor for Dexp-related operations: + const so3::DexpFunctor local(w); + + // Call applyLeftJacobian to get its Jacobians + Matrix3 H_t_w; + local.applyLeftJacobian(v, H_t_w); + + // Multiply with R^T to account for NavState::Create Jacobian. + const Matrix3 R = local.expmap(); + const Matrix3 Qt = R.transpose() * H_t_w; + + // Now compute the blocks of the LogmapDerivative Jacobian + const Matrix3 Jw = Rot3::LogmapDerivative(w); + const Matrix3 Qt2 = -Jw * Qt * Jw; + + Matrix6 J; + J << Jw, Z_3x3, Qt2, Jw; + return J; +} + /* ************************************************************************* */ Matrix6 Pose3::LogmapDerivative(const Pose3& pose) { const Vector6 xi = Logmap(pose); - const Vector3 w = xi.head<3>(); - const Matrix3 Jw = Rot3::LogmapDerivative(w); - const Matrix3 Q = ComputeQforExpmapDerivative(xi); - const Matrix3 Q2 = -Jw*Q*Jw; - Matrix6 J; - J << Jw, Z_3x3, Q2, Jw; - return J; + return LogmapDerivative(xi); } /* ************************************************************************* */ diff --git a/gtsam/geometry/Pose3.h b/gtsam/geometry/Pose3.h index 48f3253b2..baedd1c29 100644 --- a/gtsam/geometry/Pose3.h +++ b/gtsam/geometry/Pose3.h @@ -209,7 +209,10 @@ public: static Matrix6 ExpmapDerivative(const Vector6& xi); /// Derivative of Logmap - static Matrix6 LogmapDerivative(const Pose3& xi); + static Matrix6 LogmapDerivative(const Vector6& xi); + + /// Derivative of Logmap, Pose3 version. TODO(Frank): deprecate? + static Matrix6 LogmapDerivative(const Pose3& pose); // Chart at origin, depends on compile-time flag GTSAM_POSE3_EXPMAP struct GTSAM_EXPORT ChartAtOrigin { @@ -217,18 +220,6 @@ public: static Vector6 Local(const Pose3& pose, ChartJacobian Hpose = {}); }; - /** - * Compute the 3x3 bottom-left block Q of SE3 Expmap right derivative matrix - * J_r(xi) = [J_(w) Z_3x3; - * Q_r J_(w)] - * where J_(w) is the SO3 Expmap right derivative. - * (see Chirikjian11book2, pg 44, eq 10.95. - * The closed-form formula is identical to formula 102 in Barfoot14tro where - * Q_l of the SE3 Expmap left derivative matrix is given. - */ - static Matrix3 ComputeQforExpmapDerivative( - const Vector6& xi, double nearZeroThreshold = 1e-5); - using LieGroup::inverse; // version with derivative /** diff --git a/gtsam/geometry/Rot3.h b/gtsam/geometry/Rot3.h index bbdb27818..23d067c70 100644 --- a/gtsam/geometry/Rot3.h +++ b/gtsam/geometry/Rot3.h @@ -374,20 +374,13 @@ class GTSAM_EXPORT Rot3 : public LieGroup { using LieAlgebra = Matrix3; /** - * Exponential map at identity - create a rotation from canonical coordinates + * Exponential map - create a rotation from canonical coordinates * \f$ [R_x,R_y,R_z] \f$ using Rodrigues' formula */ - static Rot3 Expmap(const Vector3& v, OptionalJacobian<3,3> H = {}) { - if(H) *H = Rot3::ExpmapDerivative(v); -#ifdef GTSAM_USE_QUATERNIONS - return traits::Expmap(v); -#else - return Rot3(traits::Expmap(v)); -#endif - } + static Rot3 Expmap(const Vector3& v, OptionalJacobian<3,3> H = {}); /** - * Log map at identity - returns the canonical coordinates + * Log map - returns the canonical coordinates * \f$ [R_x,R_y,R_z] \f$ of this rotation */ static Vector3 Logmap(const Rot3& R, OptionalJacobian<3,3> H = {}); diff --git a/gtsam/geometry/Rot3M.cpp b/gtsam/geometry/Rot3M.cpp index 45e04dab6..df9217767 100644 --- a/gtsam/geometry/Rot3M.cpp +++ b/gtsam/geometry/Rot3M.cpp @@ -153,7 +153,11 @@ Point3 Rot3::rotate(const Point3& p, } /* ************************************************************************* */ -// Log map at identity - return the canonical coordinates of this rotation +Rot3 Rot3::Expmap(const Vector3& v, OptionalJacobian<3,3> H) { + return Rot3(SO3::Expmap(v, H)); +} + +/* ************************************************************************* */ Vector3 Rot3::Logmap(const Rot3& R, OptionalJacobian<3,3> H) { return SO3::Logmap(R.rot_,H); } diff --git a/gtsam/geometry/Rot3Q.cpp b/gtsam/geometry/Rot3Q.cpp index 3e50551d5..2e5b4673a 100644 --- a/gtsam/geometry/Rot3Q.cpp +++ b/gtsam/geometry/Rot3Q.cpp @@ -116,6 +116,12 @@ namespace gtsam { return Point3(r.x(), r.y(), r.z()); } + /* ************************************************************************* */ + Rot3 Rot3::Expmap(const Vector3& v, OptionalJacobian<3,3> H) { + if(H) *H = Rot3::ExpmapDerivative(v); + return traits::Expmap(v); + } + /* ************************************************************************* */ Vector3 Rot3::Logmap(const Rot3& R, OptionalJacobian<3, 3> H) { return traits::Logmap(R.quaternion_, H); diff --git a/gtsam/geometry/SO3.cpp b/gtsam/geometry/SO3.cpp index a1947953b..4d0241147 100644 --- a/gtsam/geometry/SO3.cpp +++ b/gtsam/geometry/SO3.cpp @@ -42,6 +42,20 @@ static constexpr double one_180th = 1.0 / 180.0; static constexpr double one_720th = 1.0 / 720.0; static constexpr double one_1260th = 1.0 / 1260.0; +static constexpr double kPi_inv = 1.0 / M_PI; +static constexpr double kPi2 = M_PI * M_PI; +static constexpr double k1_Pi2 = 1.0 / kPi2; +static constexpr double kPi3 = M_PI * kPi2; +static constexpr double k1_Pi3 = 1.0 / kPi3; +static constexpr double k2_Pi3 = 2.0 * k1_Pi3; +static constexpr double k1_4Pi = 0.25 * kPi_inv; // 1/(4*pi) + +// --- Thresholds --- +// Tolerance for near zero (theta^2) +static constexpr double kNearZeroThresholdSq = 1e-6; +// Tolerance for near pi (delta^2 = (pi - theta)^2) +static constexpr double kNearPiThresholdSq = 1e-6; + GTSAM_EXPORT Matrix99 Dcompose(const SO3& Q) { Matrix99 H; auto R = Q.matrix(); @@ -58,10 +72,11 @@ GTSAM_EXPORT Matrix3 compose(const Matrix3& M, const SO3& R, return MR; } -void ExpmapFunctor::init(bool nearZeroApprox) { - nearZero = - nearZeroApprox || (theta2 <= std::numeric_limits::epsilon()); +void ExpmapFunctor::init(double nearZeroThresholdSq) { + nearZero = (theta2 <= nearZeroThresholdSq); + if (!nearZero) { + // General case: Use standard stable formulas for A and B const double sin_theta = std::sin(theta); A = sin_theta / theta; const double s2 = std::sin(theta / 2.0); @@ -69,36 +84,51 @@ void ExpmapFunctor::init(bool nearZeroApprox) { 2.0 * s2 * s2; // numerically better than [1 - cos(theta)] B = one_minus_cos / theta2; } else { - // Taylor expansion at 0 + // Taylor expansion at 0 for A, B (Order theta^2) A = 1.0 - theta2 * one_6th; B = 0.5 - theta2 * one_24th; } } -ExpmapFunctor::ExpmapFunctor(const Vector3& omega, bool nearZeroApprox) +ExpmapFunctor::ExpmapFunctor(const Vector3& omega) :ExpmapFunctor(kNearZeroThresholdSq, omega) {} + +ExpmapFunctor::ExpmapFunctor(double nearZeroThresholdSq, const Vector3& omega) : theta2(omega.dot(omega)), theta(std::sqrt(theta2)), W(skewSymmetric(omega)), WW(W * W) { - init(nearZeroApprox); + init(nearZeroThresholdSq); } -ExpmapFunctor::ExpmapFunctor(const Vector3& axis, double angle, - bool nearZeroApprox) +ExpmapFunctor::ExpmapFunctor(const Vector3& axis, double angle) : theta2(angle * angle), theta(angle), W(skewSymmetric(axis * angle)), WW(W * W) { - init(nearZeroApprox); + init(kNearZeroThresholdSq); } + Matrix3 ExpmapFunctor::expmap() const { return I_3x3 + A * W + B * WW; } -DexpFunctor::DexpFunctor(const Vector3& omega, bool nearZeroApprox) - : ExpmapFunctor(omega, nearZeroApprox), omega(omega) { +DexpFunctor::DexpFunctor(const Vector3& omega, double nearZeroThresholdSq, double nearPiThresholdSq) + : ExpmapFunctor(nearZeroThresholdSq, omega), omega(omega) { if (!nearZero) { - C = (1 - A) / theta2; - D = (1.0 - A / (2.0 * B)) / theta2; + // General case or nearPi: Use standard stable formulas first + C = (1.0 - A) / theta2; // Usually stable, even near pi (1-0)/pi^2 + + // Calculate delta = pi - theta (non-negative) for nearPi check + const double delta = M_PI > theta ? M_PI - theta : 0.0; + const double delta2 = delta * delta; + const bool nearPi = (delta2 < nearPiThresholdSq); + if (nearPi) { + // Taylor expansion near pi *only for D* (Order delta) + D = k1_Pi2 + (k2_Pi3 - k1_4Pi) * delta; // D ~ 1/pi^2 + delta*(2/pi^3 - 1/(4*pi)) + } else { + // General case D: + D = (1.0 - A / (2.0 * B)) / theta2; + } + // Calculate E and F using standard formulas (stable near pi) E = (2.0 * B - A) / theta2; F = (3.0 * C - B) / theta2; } else { @@ -111,51 +141,46 @@ DexpFunctor::DexpFunctor(const Vector3& omega, bool nearZeroApprox) } } -Vector3 DexpFunctor::crossB(const Vector3& v, OptionalJacobian<3, 3> H) const { - // Wv = omega x v - const Vector3 Wv = gtsam::cross(omega, v); - if (H) { - // Apply product rule to (B Wv) - // - E * omega.transpose() is 1x3 Jacobian of B with respect to omega - // - skewSymmetric(v) is 3x3 Jacobian of Wv = gtsam::cross(omega, v) - *H = - Wv * E * omega.transpose() - B * skewSymmetric(v); - } - return B * Wv; +DexpFunctor::DexpFunctor(const Vector3& omega) + : DexpFunctor(omega, kNearZeroThresholdSq, kNearPiThresholdSq) {} + +Matrix3 DexpFunctor::rightJacobianInverse() const { + if (theta > M_PI) return rightJacobian().inverse(); + return I_3x3 + 0.5 * W + D * WW; } -Vector3 DexpFunctor::doubleCrossC(const Vector3& v, - OptionalJacobian<3, 3> H) const { - // WWv = omega x (omega x * v) - Matrix3 doubleCrossJacobian; - const Vector3 WWv = - gtsam::doubleCross(omega, v, H ? &doubleCrossJacobian : nullptr); - if (H) { - // Apply product rule to (C WWv) - // - F * omega.transpose() is 1x3 Jacobian of C with respect to omega - // doubleCrossJacobian is 3x3 Jacobian of WWv = gtsam::doubleCross(omega, v) - *H = - WWv * F * omega.transpose() + C * doubleCrossJacobian; - } - return C * WWv; +Matrix3 DexpFunctor::leftJacobianInverse() const { + if (theta > M_PI) return leftJacobian().inverse(); + return I_3x3 - 0.5 * W + D * WW; } // Multiplies v with left Jacobian through vector operations only. -Vector3 DexpFunctor::applyDexp(const Vector3& v, OptionalJacobian<3, 3> H1, - OptionalJacobian<3, 3> H2) const { - Matrix3 D_BWv_w, D_CWWv_w; - const Vector3 BWv = crossB(v, H1 ? &D_BWv_w : nullptr); - const Vector3 CWWv = doubleCrossC(v, H1 ? &D_CWWv_w : nullptr); - if (H1) *H1 = -D_BWv_w + D_CWWv_w; +Vector3 DexpFunctor::applyRightJacobian(const Vector3& v, OptionalJacobian<3, 3> H1, + OptionalJacobian<3, 3> H2) const { + const Vector3 Wv = gtsam::cross(omega, v); + + Matrix3 WWv_H_w; + const Vector3 WWv = gtsam::doubleCross(omega, v, H1 ? &WWv_H_w : nullptr); + + if (H1) { + // - E * omega.transpose() is 1x3 Jacobian of B with respect to omega + Matrix3 BWv_H_w = -Wv * E * omega.transpose() - B * skewSymmetric(v); + // - F * omega.transpose() is 1x3 Jacobian of C with respect to omega + Matrix3 CWWv_H_w = -WWv * F * omega.transpose() + C * WWv_H_w; + *H1 = -BWv_H_w + CWWv_H_w; + } + if (H2) *H2 = rightJacobian(); - return v - BWv + CWWv; + return v - B * Wv + C * WWv; } -Vector3 DexpFunctor::applyInvDexp(const Vector3& v, OptionalJacobian<3, 3> H1, - OptionalJacobian<3, 3> H2) const { +Vector3 DexpFunctor::applyRightJacobianInverse(const Vector3& v, OptionalJacobian<3, 3> H1, + OptionalJacobian<3, 3> H2) const { const Matrix3 invJr = rightJacobianInverse(); const Vector3 c = invJr * v; if (H1) { Matrix3 H; - applyDexp(c, H); // get derivative H of forward mapping + applyRightJacobian(c, H); // get derivative H of forward mapping *H1 = -invJr * H; } if (H2) *H2 = invJr; @@ -163,19 +188,26 @@ Vector3 DexpFunctor::applyInvDexp(const Vector3& v, OptionalJacobian<3, 3> H1, } Vector3 DexpFunctor::applyLeftJacobian(const Vector3& v, - OptionalJacobian<3, 3> H1, - OptionalJacobian<3, 3> H2) const { - Matrix3 D_BWv_w, D_CWWv_w; - const Vector3 BWv = crossB(v, H1 ? &D_BWv_w : nullptr); - const Vector3 CWWv = doubleCrossC(v, H1 ? &D_CWWv_w : nullptr); - if (H1) *H1 = D_BWv_w + D_CWWv_w; + OptionalJacobian<3, 3> H1, OptionalJacobian<3, 3> H2) const { + const Vector3 Wv = gtsam::cross(omega, v); + + Matrix3 WWv_H_w; + const Vector3 WWv = gtsam::doubleCross(omega, v, H1 ? &WWv_H_w : nullptr); + + if (H1) { + // - E * omega.transpose() is 1x3 Jacobian of B with respect to omega + Matrix3 BWv_H_w = -Wv * E * omega.transpose() - B * skewSymmetric(v); + // - F * omega.transpose() is 1x3 Jacobian of C with respect to omega + Matrix3 CWWv_H_w = -WWv * F * omega.transpose() + C * WWv_H_w; + *H1 = BWv_H_w + CWWv_H_w; + } + if (H2) *H2 = leftJacobian(); - return v + BWv + CWWv; + return v + B * Wv + C * WWv; } Vector3 DexpFunctor::applyLeftJacobianInverse(const Vector3& v, - OptionalJacobian<3, 3> H1, - OptionalJacobian<3, 3> H2) const { + OptionalJacobian<3, 3> H1, OptionalJacobian<3, 3> H2) const { const Matrix3 invJl = leftJacobianInverse(); const Vector3 c = invJl * v; if (H1) { @@ -250,50 +282,24 @@ Matrix3 SO3::AdjointMap() const { template <> GTSAM_EXPORT SO3 SO3::Expmap(const Vector3& omega, ChartJacobian H) { - if (H) { - so3::DexpFunctor local(omega); - *H = local.dexp(); - return SO3(local.expmap()); - } else { - return SO3(so3::ExpmapFunctor(omega).expmap()); - } + so3::DexpFunctor local(omega); + if (H) *H = local.rightJacobian(); + return SO3(local.expmap()); } template <> GTSAM_EXPORT Matrix3 SO3::ExpmapDerivative(const Vector3& omega) { - return so3::DexpFunctor(omega).dexp(); + return so3::DexpFunctor(omega).rightJacobian(); } //****************************************************************************** -/* Right Jacobian for Log map in SO(3) - equation (10.86) and following - equations in G.S. Chirikjian, "Stochastic Models, Information Theory, and Lie - Groups", Volume 2, 2008. - - logmap( Rhat * expmap(omega) ) \approx logmap(Rhat) + Jrinv * omega - - where Jrinv = LogmapDerivative(omega). This maps a perturbation on the - manifold (expmap(omega)) to a perturbation in the tangent space (Jrinv * - omega) - */ template <> GTSAM_EXPORT Matrix3 SO3::LogmapDerivative(const Vector3& omega) { - using std::cos; - using std::sin; - - double theta2 = omega.dot(omega); - if (theta2 <= std::numeric_limits::epsilon()) return I_3x3; - double theta = std::sqrt(theta2); // rotation angle - - // element of Lie algebra so(3): W = omega^ - const Matrix3 W = Hat(omega); - return I_3x3 + 0.5 * W + - (1 / (theta * theta) - (1 + cos(theta)) / (2 * theta * sin(theta))) * - W * W; + return so3::DexpFunctor(omega).rightJacobianInverse(); } -//****************************************************************************** template <> GTSAM_EXPORT Vector3 SO3::Logmap(const SO3& Q, ChartJacobian H) { @@ -306,9 +312,7 @@ Vector3 SO3::Logmap(const SO3& Q, ChartJacobian H) { const double &R21 = R(1, 0), R22 = R(1, 1), R23 = R(1, 2); const double &R31 = R(2, 0), R32 = R(2, 1), R33 = R(2, 2); - // Get trace(R) const double tr = R.trace(); - Vector3 omega; // when trace == -1, i.e., when theta = +-pi, +-3pi, +-5pi, etc. @@ -357,7 +361,7 @@ Vector3 SO3::Logmap(const SO3& Q, ChartJacobian H) { } else { double magnitude; const double tr_3 = tr - 3.0; // could be non-negative if the matrix is off orthogonal - if (tr_3 < -1e-6) { + if (tr_3 < -so3::kNearZeroThresholdSq) { // this is the normal case -1 < trace < 3 double theta = acos((tr - 1.0) / 2.0); magnitude = theta / (2.0 * sin(theta)); @@ -365,7 +369,7 @@ Vector3 SO3::Logmap(const SO3& Q, ChartJacobian H) { // when theta near 0, +-2pi, +-4pi, etc. (trace near 3.0) // use Taylor expansion: theta \approx 1/2-(t-3)/12 + O((t-3)^2) // see https://github.com/borglab/gtsam/issues/746 for details - magnitude = 0.5 - tr_3 / 12.0 + tr_3*tr_3/60.0; + magnitude = 0.5 - tr_3 * so3::one_12th + tr_3 * tr_3 * so3::one_60th; } omega = magnitude * Vector3(R32 - R23, R13 - R31, R21 - R12); } diff --git a/gtsam/geometry/SO3.h b/gtsam/geometry/SO3.h index ee51f4d83..e491cca9a 100644 --- a/gtsam/geometry/SO3.h +++ b/gtsam/geometry/SO3.h @@ -137,23 +137,26 @@ GTSAM_EXPORT Matrix99 Dcompose(const SO3& R); struct GTSAM_EXPORT ExpmapFunctor { const double theta2, theta; const Matrix3 W, WW; - bool nearZero; + bool nearZero{ false }; // Ethan Eade's constants: double A; // A = sin(theta) / theta double B; // B = (1 - cos(theta)) /// Constructor with element of Lie algebra so(3) - explicit ExpmapFunctor(const Vector3& omega, bool nearZeroApprox = false); + explicit ExpmapFunctor(const Vector3& omega); + + /// Constructor with threshold (advanced) + ExpmapFunctor(double nearZeroThresholdSq, const Vector3& axis); /// Constructor with axis-angle - ExpmapFunctor(const Vector3& axis, double angle, bool nearZeroApprox = false); + ExpmapFunctor(const Vector3& axis, double angle); /// Rodrigues formula Matrix3 expmap() const; - protected: - void init(bool nearZeroApprox = false); +protected: + void init(double nearZeroThresholdSq); }; /// Functor that implements Exponential map *and* its derivatives @@ -173,7 +176,10 @@ struct GTSAM_EXPORT DexpFunctor : public ExpmapFunctor { double F; // (3C - B) / theta2 /// Constructor with element of Lie algebra so(3) - explicit DexpFunctor(const Vector3& omega, bool nearZeroApprox = false); + explicit DexpFunctor(const Vector3& omega); + + /// Constructor with custom thresholds (advanced) + explicit DexpFunctor(const Vector3& omega, double nearZeroThresholdSq, double nearPiThresholdSq); // NOTE(luca): Right Jacobian for Exponential map in SO(3) - equation // (10.86) and following equations in G.S. Chirikjian, "Stochastic Models, @@ -186,40 +192,37 @@ struct GTSAM_EXPORT DexpFunctor : public ExpmapFunctor { // Compute the left Jacobian for Exponential map in SO(3) Matrix3 leftJacobian() const { return I_3x3 + B * W + C * WW; } - /// Differential of expmap == right Jacobian - inline Matrix3 dexp() const { return rightJacobian(); } - /// Inverse of right Jacobian - Matrix3 rightJacobianInverse() const { return I_3x3 + 0.5 * W + D * WW; } + /// For |omega|>pi uses rightJacobian().inverse(), as unstable beyond pi! + Matrix3 rightJacobianInverse() const; // Inverse of left Jacobian - Matrix3 leftJacobianInverse() const { return I_3x3 - 0.5 * W + D * WW; } + /// For |omega|>pi uses leftJacobian().inverse(), as unstable beyond pi! + Matrix3 leftJacobianInverse() const; - /// Synonym for rightJacobianInverse - inline Matrix3 invDexp() const { return rightJacobianInverse(); } + /// Multiplies with rightJacobian(), with optional derivatives + Vector3 applyRightJacobian(const Vector3& v, + OptionalJacobian<3, 3> H1 = {}, OptionalJacobian<3, 3> H2 = {}) const; - /// Computes B * (omega x v). - Vector3 crossB(const Vector3& v, OptionalJacobian<3, 3> H = {}) const; - - /// Computes C * (omega x (omega x v)). - Vector3 doubleCrossC(const Vector3& v, OptionalJacobian<3, 3> H = {}) const; - - /// Multiplies with dexp(), with optional derivatives - Vector3 applyDexp(const Vector3& v, OptionalJacobian<3, 3> H1 = {}, - OptionalJacobian<3, 3> H2 = {}) const; - - /// Multiplies with dexp().inverse(), with optional derivatives - Vector3 applyInvDexp(const Vector3& v, OptionalJacobian<3, 3> H1 = {}, - OptionalJacobian<3, 3> H2 = {}) const; + /// Multiplies with rightJacobian().inverse(), with optional derivatives + Vector3 applyRightJacobianInverse(const Vector3& v, + OptionalJacobian<3, 3> H1 = {}, OptionalJacobian<3, 3> H2 = {}) const; /// Multiplies with leftJacobian(), with optional derivatives - Vector3 applyLeftJacobian(const Vector3& v, OptionalJacobian<3, 3> H1 = {}, - OptionalJacobian<3, 3> H2 = {}) const; + Vector3 applyLeftJacobian(const Vector3& v, + OptionalJacobian<3, 3> H1 = {}, OptionalJacobian<3, 3> H2 = {}) const; /// Multiplies with leftJacobianInverse(), with optional derivatives Vector3 applyLeftJacobianInverse(const Vector3& v, - OptionalJacobian<3, 3> H1 = {}, - OptionalJacobian<3, 3> H2 = {}) const; + OptionalJacobian<3, 3> H1 = {}, OptionalJacobian<3, 3> H2 = {}) const; + +#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V43 + /// @deprecated: use rightJacobian + inline Matrix3 dexp() const { return rightJacobian(); } + + /// @deprecated: use rightJacobianInverse + inline Matrix3 invDexp() const { return rightJacobianInverse(); } +#endif }; } // namespace so3 diff --git a/gtsam/geometry/doc/Rot3.ipynb b/gtsam/geometry/doc/Rot3.ipynb index 0eb21ddae..3d370cc44 100644 --- a/gtsam/geometry/doc/Rot3.ipynb +++ b/gtsam/geometry/doc/Rot3.ipynb @@ -1014,7 +1014,7 @@ "source": [ "### Lie group operations\n", "\n", - "`Rot3` implements the Lie group operations for exponential mapping and log mapping. For more information on Lie groups and their use here, see [GTSAM concepts](https://gtsam.org/notes/GTSAM-Concepts.html)." + "`Rot3` implements the Lie group operations for exponential mapping and log mapping. For more information on Lie groups and their use here, see [GTSAM concepts](https://gtsam.org/notes/GTSAM-Concepts.html), and some detailed math in the [`SO3`](SO3.ipynb) class." ] }, { @@ -1023,51 +1023,7 @@ "id": "MmBfK0ad1KZ6" }, "source": [ - "The exponential map for $\\text{SO}(3)$ converts a 3D rotation vector (Lie algebra element in $\\mathfrak{so}(3)$) into a rotation matrix (Lie group element in $\\text{SO}(3)$). This is used to map a rotation vector $\\boldsymbol{\\omega} \\in \\mathbb{R}^3$ to a rotation matrix $R \\in \\text{SO}(3)$.\n", - "\n", - "Given a rotation vector $\\boldsymbol{\\omega} = (\\omega_x, \\omega_y, \\omega_z)$, define:\n", - "\n", - "- The rotation axis as the unit vector:\n", - " \n", - " $$\n", - " \\hat{\\omega} = \\frac{\\boldsymbol{\\omega}}{\\theta}, \\quad \\text{where } \\theta = \\|\\boldsymbol{\\omega}\\|\n", - " $$\n", - "\n", - "- The skew-symmetric matrix $[\\boldsymbol{\\omega}]_\\times$:\n", - "\n", - " $$\n", - " [\\boldsymbol{\\omega}]_\\times =\n", - " \\begin{bmatrix}\n", - " 0 & -\\omega_z & \\omega_y \\\\\n", - " \\omega_z & 0 & -\\omega_x \\\\\n", - " -\\omega_y & \\omega_x & 0\n", - " \\end{bmatrix}\n", - " $$\n", - "\n", - "Using Rodrigues' formula, the exponential map is:\n", - "\n", - "$$\n", - "\\exp([\\boldsymbol{\\omega}]_\\times) = I + \\frac{\\sin\\theta}{\\theta} [\\boldsymbol{\\omega}]_\\times + \\frac{1 - \\cos\\theta}{\\theta^2} [\\boldsymbol{\\omega}]_\\times^2\n", - "$$\n", - "\n", - "which results in the rotation matrix:\n", - "\n", - "$$\n", - "R = I + \\frac{\\sin\\theta}{\\theta} [\\boldsymbol{\\omega}]_\\times + \\frac{1 - \\cos\\theta}{\\theta^2} [\\boldsymbol{\\omega}]_\\times^2\n", - "$$\n", - "\n", - "where:\n", - "- $ I $ is the $ 3 \\times 3 $ identity matrix.\n", - "- $ \\theta $ is the magnitude of the rotation vector (rotation angle).\n", - "- $ [\\boldsymbol{\\omega}]_\\times $ represents the skew-symmetric matrix, the infinitesimal rotation generator.\n", - "\n", - "For very small $ \\theta $, we use the Taylor series approximation:\n", - "\n", - "$$\n", - "R \\approx I + [\\boldsymbol{\\omega}]_\\times\n", - "$$\n", - "\n", - "since $ \\sin\\theta \\approx \\theta$ and $ 1 - \\cos\\theta \\approx \\frac{\\theta^2}{2} $." + "The exponential map for $\\text{SO}(3)$ converts a 3D rotation vector (corresponding to a Lie algebra element in $\\mathfrak{so}(3)$) into a rotation matrix (Lie group element in $\\text{SO}(3)$). I.e., we map a rotation vector $\\boldsymbol{\\omega} \\in \\mathbb{R}^3$ to a rotation matrix $R \\in \\text{SO}(3)$." ] }, { @@ -1126,52 +1082,7 @@ "id": "Yk2nazsK6ixV" }, "source": [ - "The logarithm map for $ \\text{SO}(3) $ is the inverse of the exponential map It converts a rotation matrix $ R \\in SO(3) $ into a 3D rotation vector (a Lie algebra element in $ \\mathfrak{so}(3) $).\n", - "\n", - "Given a rotation matrix $ R $, the corresponding rotation vector $ \\boldsymbol{\\omega} \\in \\mathbb{R}^3 $ is computed as:\n", - "\n", - "$$\n", - "\\boldsymbol{\\omega} = \\theta \\hat{\\omega}\n", - "$$\n", - "\n", - "where:\n", - "- $ \\theta $ is the rotation angle:\n", - " \n", - " $$\n", - " \\theta = \\cos^{-1} \\left( \\frac{\\text{Tr}(R) - 1}{2} \\right)\n", - " $$\n", - "\n", - "- $ \\hat{\\omega} $ is the rotation axis, obtained from the skew-symmetric matrix $ [\\boldsymbol{\\omega}]_\\times $:\n", - "\n", - " $$\n", - " [\\boldsymbol{\\omega}]_\\times = \\frac{\\theta}{2 \\sin\\theta} (R - R^T)\n", - " $$\n", - "\n", - "- Extracting the components:\n", - "\n", - " $$\n", - " \\boldsymbol{\\omega} =\n", - " \\frac{\\theta}{2 \\sin\\theta} (R - R^T)^\\vee\n", - " $$\n", - "\n", - "For small $ \\theta $, we use the Taylor series approximation:\n", - "\n", - "$$\n", - "\\boldsymbol{\\omega} \\approx \\frac{1}{2} (R - R^T)^\\vee\n", - "$$\n", - "\n", - "In both cases, $ (R - R^T)^\\vee $ extracts the unique 3D vector from a skew-symmetric matrix:\n", - "\n", - "$$\n", - "(R - R^T)^\\vee=\n", - "\\begin{bmatrix}\n", - " R_{32} - R_{23} \\\\\n", - " R_{13} - R_{31} \\\\\n", - " R_{21} - R_{12}\n", - " \\end{bmatrix}\n", - "$$\n", - "\n", - "where $ R_{ij} $ are the elements of $ R $." + "The logarithm map for $ \\text{SO}(3) $ is the inverse of the exponential map It converts a rotation matrix $ R \\in SO(3) $ into a 3D rotation vector (corresponding to a Lie algebra element in $ \\mathfrak{so}(3) $)." ] }, { diff --git a/gtsam/geometry/doc/SO3.ipynb b/gtsam/geometry/doc/SO3.ipynb new file mode 100644 index 000000000..9e8224b45 --- /dev/null +++ b/gtsam/geometry/doc/SO3.ipynb @@ -0,0 +1,558 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": { + "id": "Wy0JIcGioHI9" + }, + "source": [ + "# SO3" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "YqaxPKyloJG_" + }, + "source": [ + "Typically, 3D rotations are used in GTSAM via the class [`Rot3`](Rot3.ipynb), which can use either `SO3` or `Quaternion` as the underlying representation.\n", + "\n", + "`gtsam.SO3` is the 3x3 matrix representation of an element of SO(3), and implements all the Jacobians associated with the group structure.\n", + "\n", + "This document documents some of the math involved.\n", + "\n", + "`SO3` implements the exponential map and its inverse, as well as their Jacobians. For more information on Lie groups and their use here, see [GTSAM concepts](https://gtsam.org/notes/GTSAM-Concepts.html)." + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "Hmwbhz75pcQT" + }, + "source": [ + "\"Open" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "MmBfK0ad1KZ6" + }, + "source": [ + "## The Exponential Map\n", + "\n", + "The exponential map for $\\text{SO}(3)$ converts a 3D rotation vector $\\omega$ (corresponding to a Lie algebra element $[\\boldsymbol{\\omega}]_\\times$ in $\\mathfrak{so}(3)$) into a rotation matrix (Lie group element in $\\text{SO}(3)$). I.e., we map a rotation vector $\\boldsymbol{\\omega} \\in \\mathbb{R}^3$ to a rotation matrix $R \\in \\text{SO}(3)$.\n", + "\n", + "Given a rotation vector $\\boldsymbol{\\omega} = (\\omega_x, \\omega_y, \\omega_z)$, define:\n", + "\n", + "- The rotation axis as the unit vector:\n", + " \n", + " $$\n", + " \\hat{\\omega} = \\frac{\\boldsymbol{\\omega}}{\\theta}, \\quad \\text{where } \\theta = \\|\\boldsymbol{\\omega}\\|\n", + " $$\n", + "\n", + "- The skew-symmetric matrix $[\\boldsymbol{\\omega}]_\\times$:\n", + "\n", + " $$\n", + " [\\boldsymbol{\\omega}]_\\times =\n", + " \\begin{bmatrix}\n", + " 0 & -\\omega_z & \\omega_y \\\\\n", + " \\omega_z & 0 & -\\omega_x \\\\\n", + " -\\omega_y & \\omega_x & 0\n", + " \\end{bmatrix}\n", + " $$\n", + "\n", + "Using Rodrigues' formula, the exponential map is:\n", + "\n", + "$$\n", + "\\exp([\\boldsymbol{\\omega}]_\\times) = I + \\frac{\\sin\\theta}{\\theta} [\\boldsymbol{\\omega}]_\\times + \\frac{1 - \\cos\\theta}{\\theta^2} [\\boldsymbol{\\omega}]_\\times^2\n", + "$$\n", + "\n", + "which results in the rotation matrix:\n", + "\n", + "$$\n", + "R = I + \\frac{\\sin\\theta}{\\theta} [\\boldsymbol{\\omega}]_\\times + \\frac{1 - \\cos\\theta}{\\theta^2} [\\boldsymbol{\\omega}]_\\times^2\n", + "$$\n", + "\n", + "where:\n", + "- $ I $ is the $ 3 \\times 3 $ identity matrix.\n", + "- $ \\theta $ is the magnitude of the rotation vector (rotation angle).\n", + "- $ [\\boldsymbol{\\omega}]_\\times $ represents the skew-symmetric matrix, the infinitesimal rotation generator.\n", + "\n", + "For very small $ \\theta $, we use the Taylor series approximation:\n", + "\n", + "$$\n", + "R \\approx I + [\\boldsymbol{\\omega}]_\\times\n", + "$$\n", + "\n", + "since $ \\sin\\theta \\approx \\theta$ and $ 1 - \\cos\\theta \\approx \\frac{\\theta^2}{2} $." + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "Yk2nazsK6ixV" + }, + "source": [ + "## The logarithm map\n", + "\n", + "The logarithm map for $ \\text{SO}(3) $ is the inverse of the exponential map It converts a rotation matrix $ R \\in SO(3) $ into a 3D rotation vector (corresponding to a Lie algebra element [\\boldsymbol{\\omega}]_\\times in $ \\mathfrak{so}(3) $).\n", + "\n", + "Given a rotation matrix $ R $, the corresponding rotation vector $ \\boldsymbol{\\omega} \\in \\mathbb{R}^3 $ is computed as:\n", + "\n", + "$$\n", + "\\boldsymbol{\\omega} = \\theta \\hat{\\omega}\n", + "$$\n", + "\n", + "where:\n", + "- $ \\theta $ is the rotation angle:\n", + " \n", + " $$\n", + " \\theta = \\cos^{-1} \\left( \\frac{\\text{Tr}(R) - 1}{2} \\right)\n", + " $$\n", + "\n", + "- $ \\hat{\\omega} $ is the rotation axis, obtained from the skew-symmetric matrix $ [\\boldsymbol{\\omega}]_\\times $:\n", + "\n", + " $$\n", + " [\\boldsymbol{\\omega}]_\\times = \\frac{\\theta}{2 \\sin\\theta} (R - R^T)\n", + " $$\n", + "\n", + "- Extracting the components:\n", + "\n", + " $$\n", + " \\boldsymbol{\\omega} =\n", + " \\frac{\\theta}{2 \\sin\\theta} (R - R^T)^\\vee\n", + " $$\n", + "\n", + "For small $ \\theta $, we use the Taylor series approximation:\n", + "\n", + "$$\n", + "\\boldsymbol{\\omega} \\approx \\frac{1}{2} (R - R^T)^\\vee\n", + "$$\n", + "\n", + "In both cases, $ (R - R^T)^\\vee $ extracts the unique 3D vector from a skew-symmetric matrix:\n", + "\n", + "$$\n", + "(R - R^T)^\\vee=\n", + "\\begin{bmatrix}\n", + " R_{32} - R_{23} \\\\\n", + " R_{13} - R_{31} \\\\\n", + " R_{21} - R_{12}\n", + " \\end{bmatrix}\n", + "$$\n", + "\n", + "where $ R_{ij} $ are the elements of $ R $." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Deep Dive: SO(3) Jacobians\n", + "\n", + "The Jacobians defined in SO3.h describe how small changes in the *so(3)* tangent space (represented by a 3-vector $\\omega$) relate to small changes on the SO(3) manifold (represented by rotation matrices $R$). They are crucial for tasks like uncertainty propagation, state estimation (e.g., Kalman filtering), and optimization (e.g., bundle adjustment) involving rotations.\n", + "\n", + "**Definitions:**\n", + "\n", + "Let $\\omega$ be a vector in the tangent space *so(3)*, $\\theta = \\|\\omega\\|$ be the rotation angle, and $\\Omega = \\omega^\\wedge$ be the 3x3 skew-symmetric matrix corresponding to $\\omega$. The key coefficients used are:\n", + "\n", + "* $A = \\sin(\\theta) / \\theta$\n", + "* $B = (1 - \\cos(\\theta)) / \\theta^2$\n", + "* $C = (1 - A) / \\theta^2 = (\\theta - \\sin(\\theta)) / \\theta^3$\n", + "* $D = (1 / \\theta^2) (1 - A / (2 * B))$\n", + "\n", + "Note: Taylor series expansions are used for these coefficients when $\\theta$ is close to zero for numerical stability.\n", + "\n", + "### 1. Right Jacobian (`rightJacobian`, `dexp`)\n", + "\n", + "* **Formula:** $J_r(\\omega) = I - B \\Omega + C \\Omega^2$\n", + "* **Relationship to `Expmap`:** Relates a small change $\\delta$ in the tangent space *so(3)* to the corresponding small rotation applied *on the right* on the manifold SO(3).\n", + " $$\n", + " \\text{Exp}(\\omega + \\delta) ≈ \\text{Exp}(\\omega) \\, \\text{Exp}(J_r(\\omega) \\, \\delta)\n", + " $$\n", + "* **Explanation:** This Jacobian maps a perturbation $\\delta$ in the tangent space (at the origin) to the equivalent perturbation $\\tau = J_r(\\omega) \\, \\delta$ in the tangent space *at* $R = \\text{Exp}(\\omega)$, such that the change on the manifold corresponds to right multiplication by $\\text{Exp}(\\tau)$. It represents the derivative of the exponential map considering right-composition (`dexp`). Often associated with perturbations in the **body frame**.\n", + "* **Synonyms:** Right Jacobian of Exp, `dexp`, Differential of Exp (right convention).\n", + "\n", + "### 2. Left Jacobian (`leftJacobian`)\n", + "\n", + "* **Formula:** $J_l(\\omega) = I + B \\Omega + C \\Omega^2$\n", + "* **Relationship to `Expmap`:** Relates a small change $\\delta$ in the tangent space *so(3)* to the corresponding small rotation applied *on the left* on the manifold SO(3).\n", + " $$\n", + " \\text{Exp}(\\omega + \\delta) ≈ \\text{Exp}(J_l(\\omega) \\, \\delta) \\, \\text{Exp}(\\omega)\n", + " $$\n", + "* **Explanation:** This Jacobian maps a perturbation $\\delta$ in the tangent space (at the origin) to the equivalent perturbation $\\tau = J_l(\\omega) \\, \\delta$ in the tangent space *at* $R = \\text{Exp}(\\omega)$, such that the change on the manifold corresponds to left multiplication by $\\text{Exp}(\\tau)$. Often associated with perturbations in the **world frame**. Note that $J_l(\\omega) = J_r(-omega)$.\n", + "* **Synonyms:** Left Jacobian of Exp, Differential of Exp (left convention).\n", + "\n", + "### 3. Inverse Right Jacobian (`rightJacobianInverse`, `invDexp`)\n", + "\n", + "* **Formula:** $J_r^{-1}(\\omega) = I + 0.5 \\Omega + D \\Omega^2$\n", + "* **Relationship to `Logmap`:** Relates a small rotation perturbation $\\tau$ applied *on the right* of a rotation $R = \\text{Exp}(\\omega)$ back to the resulting change in the logarithm map vector (tangent space coordinates).\n", + " $$\n", + " \\text{Log}(R \\, \\text{Exp}(\\tau)) - \\text{Log}(R) ≈ J_r^{-1}(\\omega) \\, \\tau\n", + " $$\n", + "* **Explanation:** This Jacobian maps a small rotation increment $\\tau$ (applied in the **body frame**, i.e., right multiplication) to the corresponding change in the *so(3)* coordinates $\\omega$. It is the derivative of the logarithm map when considering right perturbations. This is frequently needed in optimization algorithms that parameterize updates using right perturbations.\n", + "* **Synonyms:** Inverse Right Jacobian of Exp, `invDexp`, Right Jacobian of Log (often implied by context).\n", + "\n", + "### 4. Inverse Left Jacobian (`leftJacobianInverse`)\n", + "\n", + "* **Formula:** $J_l^{-1}(\\omega) = I - 0.5 \\Omega + D \\Omega^2$\n", + "* **Relationship to `Logmap`:** Relates a small rotation perturbation $\\tau$ applied *on the left* of a rotation $R = \\text{Exp}(\\omega)$ back to the resulting change in the logarithm map vector (tangent space coordinates).\n", + " $$\n", + " Log(\\text{Exp}(\\tau) * R) - \\text{Log}(R) ≈ J_l^{-1}(\\omega) \\, \\tau\n", + " $$\n", + "* **Explanation:** This Jacobian maps a small rotation increment $\\tau$ (applied in the **world frame**, i.e., left multiplication) to the corresponding change in the *so(3)* coordinates $\\omega$. It is the derivative of the logarithm map when considering left perturbations. Note that $J_l^{-1}(\\omega) = J_r^{-1}(-\\omega)$.\n", + "* **Synonyms:** Inverse Left Jacobian of Exp, Left Jacobian of Log (often implied by context)." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## GTSAM Convention\n", + "\n", + "GTSAM updates (retractions) for $SO(3)$ in GTSAM are performed using **right multiplication**:\n", + "$$\n", + "R_{\\text{new}} = R \\cdot \\text{Exp}(\\delta)\n", + "$$\n", + "where $\\delta \\in \\mathfrak{so}(3)$ is a tangent space increment,and hence we naturally uses the **right Jacobian $J_r(\\omega)$** for the related derivatives.\n", + "This choice is also known as **right trivialization**. This means we relate the tangent space at any rotation `R` back to the tangent space at the identity (the Lie algebra `so(3)`) using the differential of right multiplication. \n", + "\n", + "Note that this choice is **left-invariant**, because we can multiply with an arbitrary rotation matrix $R'$ on the left above, on both sides, and the update would not be affected. This term is often used in control theory, referring to how error states are defined or how system dynamics evolve relative to a world frame.\n", + "\n", + "Even with the right-multiplication convention, the left Jacobians (associated with world-frame perturbations, $R' = \\text{Exp}(\\tau) \\cdot R$) are used in several other places, most notably in Building Jacobians for the $SE(3)$ group (`Pose3`)." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Numerical Behavior near $0$ and $\\pi$\n", + "\n", + "SO(3) Jacobian Coefficients Near Zero: Taylor Expansions\n", + "\n", + "When working with the exponential map ($\\text{Exp}$) and logarithm map ($\\text{Log}$) for $SO(3)$, and especially their Jacobians, we encounter several coefficients that depend on the rotation angle $\\theta = ||\\omega||$, where $\\omega \\in \\mathfrak{so}(3)$ is the tangent vector.\n", + "\n", + "These coefficients appear in the formulas for the Jacobians and the $\\text{Exp}$ map itself:\n", + "* $\\text{Exp}(\\omega) = I + A \\cdot W + B \\cdot W^2$\n", + "* $J_r(\\omega) = I - B \\cdot W + C \\cdot W^2$ (Right Jacobian of Exp)\n", + "* $J_l(\\omega) = I + B \\cdot W + C \\cdot W^2$ (Left Jacobian of Exp)\n", + "* $J_r^{-1}(\\omega) = I + \\frac{1}{2} W + D \\cdot W^2$ (Inverse Right Jacobian)\n", + "* $J_l^{-1}(\\omega) = I - \\frac{1}{2} W + D \\cdot W^2$ (Inverse Left Jacobian)\n", + "\n", + "where $W = \\omega^\\wedge$ is the skew-symmetric matrix corresponding to $\\omega$.\n", + "\n", + "The coefficients are defined as:\n", + "* $A = \\frac{\\sin(\\theta)}{\\theta}$\n", + "* $B = \\frac{1 - \\cos(\\theta)}{\\theta^2}$\n", + "* $C = \\frac{1 - A}{\\theta^2} = \\frac{\\theta - \\sin(\\theta)}{\\theta^3}$\n", + "* $D = \\frac{1 - \\frac{A}{2B}}{\\theta^2} = \\frac{1}{ \\theta^2} \\left( 1 - \\frac{\\frac{\\sin\\theta}{\\theta}}{2 \\frac{1 - \\cos\\theta}{\\theta^2}} \\right) = \\frac{1}{\\theta^2} \\left( 1 - \\frac{\\sin\\theta}{2(1-\\cos\\theta)} \\right)$\n", + "\n", + "### The Problem Near $\\theta = 0$\n", + "\n", + "As the rotation angle $\\theta$ approaches zero, the standard formulas for these coefficients become numerically unstable due to division by zero or indeterminate forms like $0/0$.\n", + "* $A$: $\\frac{\\sin(0)}{0} \\rightarrow \\frac{0}{0}$\n", + "* $B$: $\\frac{1 - \\cos(0)}{0^2} \\rightarrow \\frac{0}{0}$\n", + "* $C$: $\\frac{0 - \\sin(0)}{0^3} \\rightarrow \\frac{0}{0}$\n", + "* $D$: Involves $A$ and $B$.\n", + "\n", + "Direct computation using floating-point arithmetic near $\\theta=0$ leads to loss of precision or `NaN` results.\n", + "\n", + "### The Solution: Taylor Series Expansions\n", + "\n", + "To maintain numerical stability and accuracy near $\\theta=0$, we replace the exact formulas with their Taylor series expansions around $\\theta=0$. GTSAM's `ExpmapFunctor` and `DexpFunctor` use expansions including the $\\theta^2$ term, which provides good accuracy for small angles.\n", + "\n", + "* $A = 1 - \\frac{\\theta^2}{6} + O(\\theta^4)$\n", + "* $B = \\frac{1}{2} - \\frac{\\theta^2}{24} + O(\\theta^4)$\n", + "* $C = \\frac{1}{6} - \\frac{\\theta^2}{120} + O(\\theta^4)$\n", + "* $D = \\frac{1}{12} + \\frac{\\theta^2}{720} + O(\\theta^4)$\n", + "\n", + "Let's visualize how well these approximations work near $\\theta=0$." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "### SO(3) Jacobian Coefficients Near Singularities: GTSAM Calculation\n", + "\n", + "This notebook visualizes how GTSAM's `DexpFunctor` calculates the Jacobian coefficients C and D near the singularities at $\\theta = 0$ and $\\theta = \\pi$. It compares the values computed by GTSAM (which uses Taylor expansions in the singular regions) against the exact mathematical formulas.\n" + ] + }, + { + "cell_type": "code", + "execution_count": 44, + "metadata": { + "tags": [ + "remove-cell" + ] + }, + "outputs": [], + "source": [ + "import numpy as np\n", + "import matplotlib.pyplot as plt\n", + "import gtsam\n", + "import math\n", + "\n", + "# --- Constants from GTSAM\n", + "near_zero_threshold_sq = 1e-6\n", + "near_pi_threshold_sq = 1e-6\n", + "\n", + "near_zero_threshold = np.sqrt(near_zero_threshold_sq)\n", + "near_pi_delta_threshold = np.sqrt(near_pi_threshold_sq) # delta = pi - theta\n", + "\n", + "# --- Define Exact Calculation Functions (for comparison) ---\n", + "# Constants for exact limits\n", + "one_6th = 1.0 / 6.0\n", + "one_12th = 1.0 / 12.0\n", + "\n", + "def A_exact(theta):\n", + " theta = np.asarray(theta)\n", + " return np.divide(np.sin(theta), theta, out=np.ones_like(theta), where=(theta != 0))\n", + "\n", + "def B_exact(theta):\n", + " theta = np.asarray(theta)\n", + " theta2 = theta**2\n", + " # Stable 1-cos using 2*sin^2(theta/2)\n", + " sin_half_theta = np.sin(theta / 2.0)\n", + " one_minus_cos = 2.0 * sin_half_theta**2\n", + " return np.divide(one_minus_cos, theta2, out=np.full_like(theta, 0.5), where=(theta2 != 0))\n", + "\n", + "def C_exact(theta):\n", + " theta = np.asarray(theta)\n", + " theta2 = theta**2\n", + " a = A_exact(theta)\n", + " # Limit C -> 1/6 as theta -> 0\n", + " return np.divide(1.0 - a, theta2, out=np.full_like(theta, one_6th), where=(theta2 != 0))\n", + "\n", + "def D_exact(theta):\n", + " theta = np.asarray(theta)\n", + " theta2 = theta**2\n", + " a = A_exact(theta)\n", + " b = B_exact(theta)\n", + " # Avoid division by zero if b is zero away from theta=0 (unlikely)\n", + " # Use np.isclose for safer check near zero? But b should be ~0.5 near theta=0\n", + " safe_b = np.where(np.abs(b) < 1e-20, 1e-20, b)\n", + " term = 1.0 - a / (2.0 * safe_b)\n", + " # Limit D -> 1/12 as theta -> 0\n", + " return np.divide(term, theta2, out=np.full_like(theta, one_12th), where=(theta2 != 0))\n", + "# --- End Exact Functions ---\n", + "\n", + "# --- Helper Function to Get GTSAM Coefficients ---\n", + "def get_gtsam_coeffs(theta_values):\n", + " \"\"\"Calculates coefficients A,B,C,D using GTSAM DexpFunctor.\"\"\"\n", + " gtsam_A, gtsam_B, gtsam_C, gtsam_D = [], [], [], []\n", + " for theta in theta_values:\n", + " if theta == 0: # Handle exact zero case if needed\n", + " omega = np.array([0.0, 0.0, 0.0])\n", + " else:\n", + " # Use a simple axis, magnitude is theta\n", + " omega = np.array([theta, 0.0, 0.0])\n", + " try:\n", + " # Instantiate the functor using the Vector3 omega\n", + " # Assuming default C++ thresholds match the python ones above\n", + " # Pass thresholds explicitly if constructor allows, e.g.:\n", + " functor = gtsam.so3.DexpFunctor(omega, 1, 1)\n", + "\n", + " # Store computed coefficients (ensure wrapper exposes these!)\n", + " gtsam_A.append(functor.A)\n", + " gtsam_B.append(functor.B)\n", + " gtsam_C.append(functor.C)\n", + " gtsam_D.append(functor.D)\n", + " except Exception as e:\n", + " print(f\"Error processing theta={theta}: {e}\")\n", + " # Pad with NaN or handle error appropriately\n", + " gtsam_A.append(np.nan)\n", + " gtsam_B.append(np.nan)\n", + " gtsam_C.append(np.nan)\n", + " gtsam_D.append(np.nan)\n", + " return (np.array(gtsam_A), np.array(gtsam_B),\n", + " np.array(gtsam_C), np.array(gtsam_D))\n", + "\n", + "def get_exact_coeffs(theta_values):\n", + " \"\"\"Calculates exact coefficients A,B,C,D.\"\"\"\n", + " return (A_exact(theta_values), B_exact(theta_values),\n", + " C_exact(theta_values), D_exact(theta_values))\n", + "\n", + "def plot_comparison(axs, theta_vals, gtsam_coeff, exact_coeff, coeff_name, threshold):\n", + " \"\"\"Helper to plot value and difference.\"\"\"\n", + " # Value Plot\n", + " axs[0].semilogx(theta_vals, gtsam_coeff, '.', markersize=2, label=f'GTSAM {coeff_name}')\n", + " axs[0].semilogx(theta_vals, exact_coeff, '--', linewidth=1, label=f'Exact {coeff_name}')\n", + " grid_which = 'both' # Use 'both' for major/minor on log scale\n", + "\n", + " if threshold is not None:\n", + " axs[0].axvline(threshold, color='r', linestyle=':', label=f'Threshold $\\\\theta \\\\approx {threshold:.2e}$') # Consistent threshold format\n", + " axs[0].set_ylabel(f'Value of {coeff_name}')\n", + " axs[0].set_title(f'Coefficient {coeff_name}')\n", + " axs[0].legend(fontsize='small')\n", + " axs[0].grid(True, which=grid_which)\n", + "\n", + " # Difference Plot\n", + " diff = np.abs(gtsam_coeff - exact_coeff)\n", + " # Avoid log(0) or very small values for plotting differences\n", + " diff = np.maximum(diff, 1e-20)\n", + "\n", + " axs[1].loglog(theta_vals, diff, 'r.', markersize=2)\n", + " axs[1].set_xscale('log') # Ensure x-axis is log\n", + " axs[1].set_yscale('log') # Ensure y-axis is log\n", + "\n", + " if threshold is not None:\n", + " axs[1].axvline(threshold, color='r', linestyle=':')\n", + " axs[1].set_ylabel('Abs. Difference |GTSAM - Exact|')\n", + " axs[1].set_title(f'Difference for {coeff_name}')\n", + " axs[1].grid(True, which=grid_which)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "### Visualization Near Zero ($\\theta \\approx 0$)" + ] + }, + { + "cell_type": "code", + "execution_count": 45, + "metadata": { + "tags": [ + "remove-input" + ] + }, + "outputs": [ + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "# Generate theta values on a log scale near zero\n", + "theta_vals_zero = np.logspace(-7, -1.5, 1000) # From 1e-7 up to ~ 1.8 degrees\n", + "\n", + "# Calculate coefficients\n", + "gtsam_A_z, gtsam_B_z, gtsam_C_z, gtsam_D_z = get_gtsam_coeffs(theta_vals_zero)\n", + "exact_A_z, exact_B_z, exact_C_z, exact_D_z = get_exact_coeffs(theta_vals_zero)\n", + "\n", + "# Plot C and D near Zero\n", + "fig_zero, axs_zero = plt.subplots(4, 2, figsize=(12, 16), sharex=True)\n", + "fig_zero.suptitle(f'GTSAM Taylor expansion vs. \"Exact\" Formula Near Zero\\n(Crossover at $\\\\theta \\\\approx {near_zero_threshold:.2e}$ rad)', fontsize=14)\n", + "\n", + "plot_comparison(axs_zero[0,:], theta_vals_zero, gtsam_A_z, exact_A_z, 'A', near_zero_threshold)\n", + "plot_comparison(axs_zero[1,:], theta_vals_zero, gtsam_B_z, exact_B_z, 'B', near_zero_threshold)\n", + "plot_comparison(axs_zero[2,:], theta_vals_zero, gtsam_C_z, exact_C_z, 'C', near_zero_threshold)\n", + "plot_comparison(axs_zero[3,:], theta_vals_zero, gtsam_D_z, exact_D_z, 'D', near_zero_threshold)\n", + "\n", + "axs_zero[1, 0].set_xlabel(\"$\\\\theta$ (radians)\")\n", + "axs_zero[1, 1].set_xlabel(\"$\\\\theta$ (radians)\")\n", + "plt.tight_layout(rect=[0, 0.03, 1, 0.95]) # Adjust layout to prevent title overlap\n", + "plt.show()" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "**Interpretation Near Zero:**\n", + "The plots show the *Taylor expansion* values computed by GTSAM (`.` markers) and the \"exact\" mathematical formulas (`--` lines). The red dotted line indicates the threshold $\\theta = \\sqrt{10^{-5}} \\approx 0.00316$ radians.\n", + "\n", + "For A and B, the difference plot shows that the Taylor expansion introduces a small approximation error below the threshold. The error increases as $\\theta$ moves away from 0. ForC and D the exact formula is itself hard to compute accurately, but we see that the error of the Taylor expansion starts going up only far from the threshold. " + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Visualization Near Pi ($\\theta \\approx \\pi$)\n", + "GTSAM specifically uses a Taylor expansion for coefficient **D** near $\\pi$, as the standard formula becomes unstable. Other coefficients (A, B, C) are typically computed using their standard, stable forms near $\\pi$." + ] + }, + { + "cell_type": "code", + "execution_count": 46, + "metadata": { + "tags": [ + "remove-input" + ] + }, + "outputs": [ + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "# Generate theta values on a linear scale near pi\n", + "theta_vals_pi = np.linspace(\n", + " math.pi - 0.1, math.pi - 1e-9, 1000\n", + ") # Approach pi from below, up to ~6 deg away\n", + "\n", + "# Calculate coefficients\n", + "gtsam_A_p, gtsam_B_p, gtsam_C_p, gtsam_D_p = get_gtsam_coeffs(theta_vals_pi)\n", + "exact_A_p, exact_B_p, exact_C_p, exact_D_p = get_exact_coeffs(theta_vals_pi)\n", + "\n", + "# Calculate the theta value corresponding to the delta threshold\n", + "near_pi_theta_threshold = math.pi - near_pi_delta_threshold\n", + "\n", + "# Plot only D near Pi\n", + "fig_pi, axs_pi = plt.subplots(1, 2, figsize=(12, 5))\n", + "fig_pi.suptitle(\n", + " r'GTSAM Taylor expansion vs. \"Exact\" Formula Near Pi'\n", + " + f\"\\n(Crossover at $\\\\theta \\\\approx {near_pi_theta_threshold:.3f}$ rad, i.e., $\\\\delta \\\\approx {near_pi_delta_threshold:.2e}$ rad)\",\n", + " fontsize=14,\n", + ")\n", + "\n", + "plot_comparison(axs_pi, theta_vals_pi, gtsam_D_p, exact_D_p, \"D\", near_pi_theta_threshold)\n", + "\n", + "axs_pi[0].set_xlabel(\"$\\\\theta$ (radians)\")\n", + "axs_pi[1].set_xlabel(\"$\\\\theta$ (radians)\")\n", + "plt.tight_layout(rect=[0, 0.03, 1, 0.93])\n", + "plt.show()" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "**Interpretation Near Pi:**\n", + "The plots focus on coefficient D as $\\theta$ approaches $\\pi$. The red dotted line indicates the threshold $\\theta = \\pi - \\sqrt{10^{-3}} \\approx \\pi - 0.0316$ radians.\n", + "\n", + "We only plot the Taylor expansion. To the right of the threshold (closer to $\\pi$) GTSAM will use this, and the difference plot shows the approximation error introduced by this Taylor expansion is small (less than $10e-8$)." + ] + } + ], + "metadata": { + "colab": { + "provenance": [] + }, + "kernelspec": { + "display_name": "py312", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.12.6" + } + }, + "nbformat": 4, + "nbformat_minor": 0 +} diff --git a/gtsam/geometry/geometry.i b/gtsam/geometry/geometry.i index 2c8e2f9ab..3520ab140 100644 --- a/gtsam/geometry/geometry.i +++ b/gtsam/geometry/geometry.i @@ -198,6 +198,39 @@ class Rot2 { }; #include + +namespace so3 { + class ExpmapFunctor { + const double theta2; + const double theta; + const Matrix3 W; + const Matrix3 WW; + const bool nearZero; + double A; // A = sin(theta) / theta + double B; // B = (1 - cos(theta)) + ExpmapFunctor(const gtsam::Vector3& omega); + ExpmapFunctor(double nearZeroThresholdSq, const gtsam::Vector3& axis); + ExpmapFunctor(const gtsam::Vector3& axis, double angle); + gtsam::Matrix3 expmap() const; + }; + + virtual class DexpFunctor : gtsam::so3::ExpmapFunctor { + const gtsam::Vector3 omega; + const double C; // (1 - A) / theta^2 + const double D; // (1 - A/2B) / theta2 + DexpFunctor(const gtsam::Vector3& omega); + DexpFunctor(const gtsam::Vector3& omega, double nearZeroThresholdSq, double nearPiThresholdSq); + gtsam::Matrix3 rightJacobian() const; + gtsam::Matrix3 leftJacobian() const; + gtsam::Matrix3 rightJacobianInverse() const; + gtsam::Matrix3 leftJacobianInverse() const; + gtsam::Vector3 applyRightJacobian(const gtsam::Vector3& v) const; + gtsam::Vector3 applyRightJacobianInverse(const gtsam::Vector3& v) const; + gtsam::Vector3 applyLeftJacobian(const gtsam::Vector3& v) const; + gtsam::Vector3 applyLeftJacobianInverse(const gtsam::Vector3& v) const; + }; +} + class SO3 { // Standard Constructors SO3(); @@ -220,21 +253,22 @@ class SO3 { gtsam::SO3 operator*(const gtsam::SO3& R) const; // Lie Group - static gtsam::SO3 Expmap(gtsam::Vector v); - static gtsam::Vector Logmap(const gtsam::SO3& p); - gtsam::SO3 expmap(gtsam::Vector v); - gtsam::Vector logmap(const gtsam::SO3& p); - static gtsam::Matrix Hat(const gtsam::Vector& xi); - static gtsam::Vector Vee(const gtsam::Matrix& xi); + static gtsam::SO3 Expmap(gtsam::Vector3 v); + static gtsam::Vector3 Logmap(const gtsam::SO3& p); + static gtsam::Matrix3 ExpmapDerivative(const gtsam::Vector3& omega); + static gtsam::Matrix3 LogmapDerivative(const gtsam::Vector3& omega); + gtsam::SO3 expmap(gtsam::Vector3 v); + gtsam::Vector3 logmap(const gtsam::SO3& p); + static gtsam::Matrix3 Hat(const gtsam::Vector3& xi); + static gtsam::Vector3 Vee(const gtsam::Matrix3& xi); // Manifold - gtsam::SO3 retract(gtsam::Vector v) const; - gtsam::Vector localCoordinates(const gtsam::SO3& R) const; - static gtsam::SO3 Expmap(gtsam::Vector v); + gtsam::SO3 retract(gtsam::Vector3 v) const; + gtsam::Vector3 localCoordinates(const gtsam::SO3& R) const; // Other methods - gtsam::Vector vec() const; - gtsam::Matrix matrix() const; + gtsam::Vector3 vec() const; + gtsam::Matrix3 matrix() const; }; #include @@ -376,6 +410,8 @@ class Rot3 { // Lie group static gtsam::Rot3 Expmap(gtsam::Vector v); static gtsam::Vector Logmap(const gtsam::Rot3& R); + static gtsam::Matrix3 ExpmapDerivative(const gtsam::Vector3& omega); + static gtsam::Matrix3 LogmapDerivative(const gtsam::Vector3& omega); gtsam::Rot3 expmap(const gtsam::Vector& v); gtsam::Vector logmap(const gtsam::Rot3& p); static gtsam::Matrix Hat(const gtsam::Vector& xi); @@ -532,12 +568,17 @@ class Pose3 { // Lie Group static gtsam::Pose3 Expmap(gtsam::Vector xi); static gtsam::Vector Logmap(const gtsam::Pose3& p); + static gtsam::Matrix6 ExpmapDerivative(const gtsam::Vector6& xi); + static gtsam::Matrix6 LogmapDerivative(const gtsam::Vector6& xi); + static gtsam::Matrix6 LogmapDerivative(const gtsam::Pose3& xi); static gtsam::Pose3 Expmap(gtsam::Vector xi, Eigen::Ref Hxi); static gtsam::Vector Logmap(const gtsam::Pose3& pose, Eigen::Ref Hpose); + gtsam::Pose3 expmap(gtsam::Vector v); gtsam::Pose3 expmap(gtsam::Vector v, Eigen::Ref H1, Eigen::Ref H2); gtsam::Vector logmap(const gtsam::Pose3& p); gtsam::Vector logmap(const gtsam::Pose3& p, Eigen::Ref H1, Eigen::Ref H2); + gtsam::Matrix AdjointMap() const; gtsam::Vector Adjoint(gtsam::Vector xi_b) const; gtsam::Vector Adjoint(gtsam::Vector xi_b, Eigen::Ref H_this, @@ -550,8 +591,7 @@ class Pose3 { static gtsam::Matrix adjointMap_(gtsam::Vector xi); static gtsam::Vector adjoint_(gtsam::Vector xi, gtsam::Vector y); static gtsam::Vector adjointTranspose(gtsam::Vector xi, gtsam::Vector y); - static gtsam::Matrix ExpmapDerivative(gtsam::Vector xi); - static gtsam::Matrix LogmapDerivative(const gtsam::Pose3& xi); + static gtsam::Matrix Hat(const gtsam::Vector& xi); static gtsam::Vector Vee(const gtsam::Matrix& X); diff --git a/gtsam/geometry/tests/testPose3.cpp b/gtsam/geometry/tests/testPose3.cpp index c33985aad..0b59f9724 100644 --- a/gtsam/geometry/tests/testPose3.cpp +++ b/gtsam/geometry/tests/testPose3.cpp @@ -891,14 +891,14 @@ TEST(Pose3, ExpmapDerivative) { //****************************************************************************** namespace test_cases { -std::vector small{{0, 0, 0}, // - {1e-5, 0, 0}, {0, 1e-5, 0}, {0, 0, 1e-5}, //, - {1e-4, 0, 0}, {0, 1e-4, 0}, {0, 0, 1e-4}}; -std::vector large{{0, 0, 0}, {1, 0, 0}, {0, 1, 0}, - {0, 0, 1}, {.1, .2, .3}, {1, -2, 3}}; -auto omegas = [](bool nearZero) { return nearZero ? small : large; }; -std::vector vs{{1, 0, 0}, {0, 1, 0}, {0, 0, 1}, - {.4, .3, .2}, {4, 5, 6}, {-10, -20, 30}}; + static const std::vector small{ {0, 0, 0}, // + {1e-5, 0, 0}, {0, 1e-5, 0}, {0, 0, 1e-5}, //, + {1e-4, 0, 0}, {0, 1e-4, 0}, {0, 0, 1e-4} }; + static const std::vector large{ {0, 0, 0}, {1, 0, 0}, {0, 1, 0}, + {0, 0, 1}, {.1, .2, .3}, {1, -2, 3} }; + auto omegas = [](bool nearZero) -> const std::vector&{ return nearZero ? small : large; }; + static const std::vector vs{ {1, 0, 0}, {0, 1, 0}, {0, 0, 1}, + {.4, .3, .2}, {4, 5, 6}, {-10, -20, 30} }; } // namespace test_cases //****************************************************************************** @@ -936,7 +936,9 @@ TEST(Pose3, Logmap) { TEST(Pose3, LogmapDerivatives) { for (bool nearZero : {true, false}) { for (const Vector3& w : test_cases::omegas(nearZero)) { + std::cout << "w: " << w.transpose() << std::endl; for (Vector3 v : test_cases::vs) { + std::cout << "v: " << v.transpose() << std::endl; const Vector6 xi = (Vector6() << w, v).finished(); Pose3 pose = Pose3::Expmap(xi); const Matrix6 expectedH = @@ -956,6 +958,59 @@ TEST(Pose3, LogmapDerivatives) { } } +//****************************************************************************** +TEST(Pose3, LogmapDerivative) { + // Copied from testSO3.cpp + const Rot3 R2((Matrix3() << // Near pi + -0.750767, -0.0285082, -0.659952, + -0.0102558, -0.998445, 0.0547974, + -0.660487, 0.0479084, 0.749307).finished()); + const Rot3 R3((Matrix3() << // Near pi + -0.747473, -0.00190019, -0.664289, + -0.0385114, -0.99819, 0.0461892, + -0.663175, 0.060108, 0.746047).finished()); + const Rot3 R4((Matrix3() << // Final pose in a drone experiment + 0.324237, 0.902975, 0.281968, + -0.674322, 0.429668, -0.600562, + -0.663445, 0.00458662, 0.748211).finished()); + + // Now creates poses + const Pose3 T0; // Identity + const Vector6 xi(0.1, -0.1, 0.1, 0.1, -0.1, 0.1); + const Pose3 T1 = Pose3::Expmap(xi); // Small rotation + const Pose3 T2(R2, Point3(1, 2, 3)); + const Pose3 T3(R3, Point3(1, 2, 3)); + const Pose3 T4(R4, Point3(1, 2, 3)); + size_t i = 0; + for (const Pose3& T : { T0, T1, T2, T3, T4 }) { + const bool nearPi = (i == 2 || i == 3); // Flag cases near pi + + Matrix6 actualH; // H computed by Logmap(T, H) using LogmapDerivative(xi) + const Vector6 xi = Pose3::Logmap(T, actualH); + + // 1. Check self-consistency of analytical derivative calculation: + // Does the H returned by Logmap match an independent calculation + // of J_r^{-1} using ExpmapDerivative with the computed xi? + Matrix6 J_r_inv = Pose3::ExpmapDerivative(xi).inverse(); // J_r^{-1} + EXPECT(assert_equal(J_r_inv, actualH)); // This test is crucial and should pass + + // 2. Check analytical derivative against numerical derivative: + // Only perform this check AWAY from the pi singularity, where + // numerical differentiation of Logmap is expected to be reliable + // and should match the analytical derivative. + if (!nearPi) { + const Matrix expectedH = numericalDerivative11( + std::bind(&Pose3::Logmap, std::placeholders::_1, nullptr), T, 1e-7); + EXPECT(assert_equal(expectedH, actualH, 1e-5)); // 1e-5 needed to pass R4 + } + else { + // We accept that the numerical derivative of this specific Logmap implementation + // near pi will not match the standard analytical derivative J_r^{-1}. + } + i++; + } +} + /* ************************************************************************* */ Vector6 testDerivAdjoint(const Vector6& xi, const Vector6& v) { return Pose3::adjointMap(xi) * v; diff --git a/gtsam/geometry/tests/testSO3.cpp b/gtsam/geometry/tests/testSO3.cpp index 3f06624e1..f0b3cad65 100644 --- a/gtsam/geometry/tests/testSO3.cpp +++ b/gtsam/geometry/tests/testSO3.cpp @@ -274,44 +274,72 @@ TEST(SO3, ExpmapDerivative5) { //****************************************************************************** TEST(SO3, ExpmapDerivative6) { - const Vector3 thetahat(0.1, 0, 0.1); - const Matrix Jexpected = numericalDerivative11( - std::bind(&SO3::Expmap, std::placeholders::_1, nullptr), thetahat); - Matrix3 Jactual; - SO3::Expmap(thetahat, Jactual); - EXPECT(assert_equal(Jexpected, Jactual)); + const Vector3 theta(0.1, 0, 0.1); + const Matrix expectedH = numericalDerivative11( + std::bind(&SO3::Expmap, std::placeholders::_1, nullptr), theta); + Matrix3 actualH; + SO3::Expmap(theta, actualH); + EXPECT(assert_equal(expectedH, actualH)); } //****************************************************************************** TEST(SO3, LogmapDerivative) { - const Vector3 thetahat(0.1, 0, 0.1); - const SO3 R = SO3::Expmap(thetahat); // some rotation - const Matrix Jexpected = numericalDerivative11( - std::bind(&SO3::Logmap, std::placeholders::_1, nullptr), R); - const Matrix3 Jactual = SO3::LogmapDerivative(thetahat); - EXPECT(assert_equal(Jexpected, Jactual)); -} + const SO3 R0; // Identity + const Vector3 omega1(0.1, 0, 0.1); + const SO3 R1 = SO3::Expmap(omega1); // Small rotation + const SO3 R2((Matrix3() << // Near pi + -0.750767, -0.0285082, -0.659952, + -0.0102558, -0.998445, 0.0547974, + -0.660487, 0.0479084, 0.749307).finished()); + const SO3 R3((Matrix3() << // Near pi + -0.747473, -0.00190019, -0.664289, + -0.0385114, -0.99819, 0.0461892, + -0.663175, 0.060108, 0.746047).finished()); + const SO3 R4((Matrix3() << // Final pose in a drone experiment + 0.324237, 0.902975, 0.281968, + -0.674322, 0.429668, -0.600562, + -0.663445, 0.00458662, 0.748211).finished()); + size_t i = 0; + for (const SO3& R : { R0, R1, R2, R3, R4 }) { + const bool nearPi = (i == 2 || i == 3); // Flag cases near pi -//****************************************************************************** -TEST(SO3, JacobianLogmap) { - const Vector3 thetahat(0.1, 0, 0.1); - const SO3 R = SO3::Expmap(thetahat); // some rotation - const Matrix Jexpected = numericalDerivative11( - std::bind(&SO3::Logmap, std::placeholders::_1, nullptr), R); - Matrix3 Jactual; - SO3::Logmap(R, Jactual); - EXPECT(assert_equal(Jexpected, Jactual)); -} + Matrix3 actualH; // H computed by Logmap(R, H) using LogmapDerivative(omega) + const Vector3 omega = SO3::Logmap(R, actualH); + // 1. Check self-consistency of analytical derivative calculation: + // Does the H returned by Logmap match an independent calculation + // of J_r^{-1} using DexpFunctor with the computed omega? + so3::DexpFunctor local(omega); + Matrix3 J_r_inv = local.rightJacobianInverse(); // J_r^{-1} via DexpFunctor + EXPECT(assert_equal(J_r_inv, actualH)); // This test is crucial and should pass + + // 2. Check analytical derivative against numerical derivative: + // Only perform this check AWAY from the pi singularity, where + // numerical differentiation of Logmap is expected to be reliable + // and should match the analytical derivative. + if (!nearPi) { + const Matrix expectedH = numericalDerivative11( + std::bind(&SO3::Logmap, std::placeholders::_1, nullptr), R, 1e-7); + EXPECT(assert_equal(expectedH, actualH, 1e-6)); // 1e-6 needed to pass R4 + } + else { + // We accept that the numerical derivative of this specific Logmap implementation + // near pi will not match the standard analytical derivative J_r^{-1}. + } + i++; + } +} //****************************************************************************** namespace test_cases { -std::vector small{{0, 0, 0}, // - {1e-5, 0, 0}, {0, 1e-5, 0}, {0, 0, 1e-5}, //, - {1e-4, 0, 0}, {0, 1e-4, 0}, {0, 0, 1e-4}}; -std::vector large{ - {0, 0, 0}, {1, 0, 0}, {0, 1, 0}, {0, 0, 1}, {0.1, 0.2, 0.3}}; -auto omegas = [](bool nearZero) { return nearZero ? small : large; }; -std::vector vs{{1, 0, 0}, {0, 1, 0}, {0, 0, 1}, {0.4, 0.3, 0.2}}; + std::vector small{ {0, 0, 0}, // + {1e-5, 0, 0}, {0, 1e-5, 0}, {0, 0, 1e-5}, //, + {1e-4, 0, 0}, {0, 1e-4, 0}, {0, 0, 1e-4} }; + std::vector large{ + {0, 0, 0}, {1, 0, 0}, {0, 1, 0}, {0, 0, 1}, {0.1, 0.2, 0.3}, + {0.4, 0.5, 0.6}, {0.7, 0.8, 0.9}, {1.1, 1.2, 1.3}, {1.4, 1.5, 1.6}, + {1.7, 1.8, 1.9}, {2, 2, 2}, {3, 3, 3}, {4, 4, 4}, {5, 5, 5} }; + auto omegas = [](bool nearZero) { return nearZero ? small : large; }; + std::vector vs{ {1, 0, 0}, {0, 1, 0}, {0, 0, 1}, {0.4, 0.3, 0.2} }; } // namespace test_cases //****************************************************************************** @@ -319,86 +347,50 @@ TEST(SO3, JacobianInverses) { Matrix HR, HL; for (bool nearZero : {true, false}) { for (const Vector3& omega : test_cases::omegas(nearZero)) { - so3::DexpFunctor local(omega, nearZero); + so3::DexpFunctor local(omega, nearZero ? 1.0 : 0.0, 1e-5); EXPECT(assert_equal(local.rightJacobian().inverse(), - local.rightJacobianInverse())); + local.rightJacobianInverse())); EXPECT(assert_equal(local.leftJacobian().inverse(), - local.leftJacobianInverse())); + local.leftJacobianInverse())); } } } //****************************************************************************** -TEST(SO3, CrossB) { - Matrix aH1; - for (bool nearZero : {true, false}) { - std::function f = - [nearZero](const Vector3& omega, const Vector3& v) { - return so3::DexpFunctor(omega, nearZero).crossB(v); - }; - for (const Vector3& omega : test_cases::omegas(nearZero)) { - so3::DexpFunctor local(omega, nearZero); - for (const Vector3& v : test_cases::vs) { - local.crossB(v, aH1); - EXPECT(assert_equal(numericalDerivative21(f, omega, v), aH1)); - } - } - } -} - -//****************************************************************************** -TEST(SO3, DoubleCrossC) { - Matrix aH1; - for (bool nearZero : {true, false}) { - std::function f = - [nearZero](const Vector3& omega, const Vector3& v) { - return so3::DexpFunctor(omega, nearZero).doubleCrossC(v); - }; - for (const Vector3& omega : test_cases::omegas(nearZero)) { - so3::DexpFunctor local(omega, nearZero); - for (const Vector3& v : test_cases::vs) { - local.doubleCrossC(v, aH1); - EXPECT(assert_equal(numericalDerivative21(f, omega, v), aH1)); - } - } - } -} - -//****************************************************************************** -TEST(SO3, ApplyDexp) { +TEST(SO3, ApplyRightJacobian) { Matrix aH1, aH2; for (bool nearZero : {true, false}) { std::function f = - [nearZero](const Vector3& omega, const Vector3& v) { - return so3::DexpFunctor(omega, nearZero).applyDexp(v); - }; + [nearZero](const Vector3& omega, const Vector3& v) { + return so3::DexpFunctor(omega, nearZero ? 1.0 : 0.0, 1e-5).applyRightJacobian(v); + }; for (const Vector3& omega : test_cases::omegas(nearZero)) { - so3::DexpFunctor local(omega, nearZero); + so3::DexpFunctor local(omega, nearZero ? 1.0 : 0.0, 1e-5); for (const Vector3& v : test_cases::vs) { - EXPECT(assert_equal(Vector3(local.dexp() * v), - local.applyDexp(v, aH1, aH2))); + EXPECT(assert_equal(Vector3(local.rightJacobian() * v), + local.applyRightJacobian(v, aH1, aH2))); EXPECT(assert_equal(numericalDerivative21(f, omega, v), aH1)); EXPECT(assert_equal(numericalDerivative22(f, omega, v), aH2)); - EXPECT(assert_equal(local.dexp(), aH2)); + EXPECT(assert_equal(local.rightJacobian(), aH2)); } } } } //****************************************************************************** -TEST(SO3, ApplyInvDexp) { +TEST(SO3, ApplyRightJacobianInverse) { Matrix aH1, aH2; for (bool nearZero : {true, false}) { std::function f = - [nearZero](const Vector3& omega, const Vector3& v) { - return so3::DexpFunctor(omega, nearZero).applyInvDexp(v); - }; + [nearZero](const Vector3& omega, const Vector3& v) { + return so3::DexpFunctor(omega, nearZero ? 1.0 : 0.0, 1e-5).applyRightJacobianInverse(v); + }; for (const Vector3& omega : test_cases::omegas(nearZero)) { - so3::DexpFunctor local(omega, nearZero); + so3::DexpFunctor local(omega, nearZero ? 1.0 : 0.0, 1e-5); Matrix invJr = local.rightJacobianInverse(); for (const Vector3& v : test_cases::vs) { EXPECT( - assert_equal(Vector3(invJr * v), local.applyInvDexp(v, aH1, aH2))); + assert_equal(Vector3(invJr * v), local.applyRightJacobianInverse(v, aH1, aH2))); EXPECT(assert_equal(numericalDerivative21(f, omega, v), aH1)); EXPECT(assert_equal(numericalDerivative22(f, omega, v), aH2)); EXPECT(assert_equal(invJr, aH2)); @@ -412,14 +404,14 @@ TEST(SO3, ApplyLeftJacobian) { Matrix aH1, aH2; for (bool nearZero : {true, false}) { std::function f = - [nearZero](const Vector3& omega, const Vector3& v) { - return so3::DexpFunctor(omega, nearZero).applyLeftJacobian(v); - }; + [nearZero](const Vector3& omega, const Vector3& v) { + return so3::DexpFunctor(omega, nearZero ? 1.0 : 0.0, 1e-5).applyLeftJacobian(v); + }; for (const Vector3& omega : test_cases::omegas(nearZero)) { - so3::DexpFunctor local(omega, nearZero); + so3::DexpFunctor local(omega, nearZero ? 1.0 : 0.0, 1e-5); for (const Vector3& v : test_cases::vs) { EXPECT(assert_equal(Vector3(local.leftJacobian() * v), - local.applyLeftJacobian(v, aH1, aH2))); + local.applyLeftJacobian(v, aH1, aH2))); EXPECT(assert_equal(numericalDerivative21(f, omega, v), aH1)); EXPECT(assert_equal(numericalDerivative22(f, omega, v), aH2)); EXPECT(assert_equal(local.leftJacobian(), aH2)); @@ -433,15 +425,15 @@ TEST(SO3, ApplyLeftJacobianInverse) { Matrix aH1, aH2; for (bool nearZero : {true, false}) { std::function f = - [nearZero](const Vector3& omega, const Vector3& v) { - return so3::DexpFunctor(omega, nearZero).applyLeftJacobianInverse(v); - }; + [nearZero](const Vector3& omega, const Vector3& v) { + return so3::DexpFunctor(omega, nearZero ? 1.0 : 0.0, 1e-5).applyLeftJacobianInverse(v); + }; for (const Vector3& omega : test_cases::omegas(nearZero)) { - so3::DexpFunctor local(omega, nearZero); + so3::DexpFunctor local(omega, nearZero ? 1.0 : 0.0, 1e-5); Matrix invJl = local.leftJacobianInverse(); for (const Vector3& v : test_cases::vs) { EXPECT(assert_equal(Vector3(invJl * v), - local.applyLeftJacobianInverse(v, aH1, aH2))); + local.applyLeftJacobianInverse(v, aH1, aH2))); EXPECT(assert_equal(numericalDerivative21(f, omega, v), aH1)); EXPECT(assert_equal(numericalDerivative22(f, omega, v), aH2)); EXPECT(assert_equal(invJl, aH2)); diff --git a/gtsam/linear/linear.i b/gtsam/linear/linear.i index 587d3bcf3..de55a5bb4 100644 --- a/gtsam/linear/linear.i +++ b/gtsam/linear/linear.i @@ -657,6 +657,21 @@ virtual class GaussianBayesNet { }; #include +class GaussianBayesTreeClique { + GaussianBayesTreeClique(); + GaussianBayesTreeClique(const gtsam::GaussianConditional* conditional); + bool equals(const gtsam::GaussianBayesTreeClique& other, double tol) const; + void print(string s = "", const gtsam::KeyFormatter& keyFormatter = + gtsam::DefaultKeyFormatter); + const gtsam::GaussianConditional* conditional() const; + bool isRoot() const; + gtsam::GaussianBayesTreeClique* parent() const; + size_t nrChildren() const; + gtsam::GaussianBayesTreeClique* operator[](size_t j) const; + size_t treeSize() const; + size_t numCachedSeparatorMarginals() const; + void deleteCachedShortcuts(); +}; virtual class GaussianBayesTree { // Standard Constructors and Named Constructors GaussianBayesTree(); @@ -666,6 +681,8 @@ virtual class GaussianBayesTree { gtsam::DefaultKeyFormatter); size_t size() const; bool empty() const; + const GaussianBayesTree::Roots& roots() const; + const gtsam::GaussianBayesTreeClique* operator[](size_t j) const; size_t numCachedSeparatorMarginals() const; string dot(const gtsam::KeyFormatter& keyFormatter = diff --git a/gtsam/navigation/NavState.cpp b/gtsam/navigation/NavState.cpp index 50907db25..8b1388cba 100644 --- a/gtsam/navigation/NavState.cpp +++ b/gtsam/navigation/NavState.cpp @@ -118,8 +118,7 @@ NavState NavState::Expmap(const Vector9& xi, OptionalJacobian<9, 9> Hxi) { Vector3 w = xi.head<3>(), rho = xi.segment<3>(3), nu = xi.tail<3>(); // Instantiate functor for Dexp-related operations: - const bool nearZero = (w.dot(w) <= 1e-5); - const so3::DexpFunctor local(w, nearZero); + const so3::DexpFunctor local(w); // Compute rotation using Expmap #ifdef GTSAM_USE_QUATERNIONS @@ -238,15 +237,13 @@ Matrix9 NavState::ExpmapDerivative(const Vector9& xi) { } //------------------------------------------------------------------------------ -Matrix9 NavState::LogmapDerivative(const NavState& state) { - const Vector9 xi = Logmap(state); +Matrix9 NavState::LogmapDerivative(const Vector9& xi) { const Vector3 w = xi.head<3>(); Vector3 rho = xi.segment<3>(3); Vector3 nu = xi.tail<3>(); // Instantiate functor for Dexp-related operations: - const bool nearZero = (w.dot(w) <= 1e-5); - const so3::DexpFunctor local(w, nearZero); + const so3::DexpFunctor local(w); // Call applyLeftJacobian to get its Jacobians Matrix3 H_t_w, H_v_w; @@ -270,6 +267,12 @@ Matrix9 NavState::LogmapDerivative(const NavState& state) { return J; } +//------------------------------------------------------------------------------ +Matrix9 NavState::LogmapDerivative(const NavState& state) { + const Vector9 xi = Logmap(state); + return LogmapDerivative(xi); +} + //------------------------------------------------------------------------------ Matrix5 NavState::Hat(const Vector9& xi) { Matrix5 X; diff --git a/gtsam/navigation/NavState.h b/gtsam/navigation/NavState.h index 6c93a6b94..ba56fafe1 100644 --- a/gtsam/navigation/NavState.h +++ b/gtsam/navigation/NavState.h @@ -245,6 +245,9 @@ public: static Matrix9 ExpmapDerivative(const Vector9& xi); /// Derivative of Logmap + static Matrix9 LogmapDerivative(const Vector9& xi); + + /// Derivative of Logmap, NavState version static Matrix9 LogmapDerivative(const NavState& xi); // Chart at origin, depends on compile-time flag GTSAM_POSE3_EXPMAP diff --git a/gtsam/navigation/TangentPreintegration.cpp b/gtsam/navigation/TangentPreintegration.cpp index 52f730cbb..97b3c425b 100644 --- a/gtsam/navigation/TangentPreintegration.cpp +++ b/gtsam/navigation/TangentPreintegration.cpp @@ -66,7 +66,7 @@ Vector9 TangentPreintegration::UpdatePreintegrated(const Vector3& a_body, // Calculate exact mean propagation Matrix3 w_tangent_H_theta, invH; const Vector3 w_tangent = // angular velocity mapped back to tangent space - local.applyInvDexp(w_body, A ? &w_tangent_H_theta : 0, C ? &invH : 0); + local.applyRightJacobianInverse(w_body, A ? &w_tangent_H_theta : 0, C ? &invH : 0); const Rot3 R(local.expmap()); // nRb: rotation of body in nav frame const Vector3 a_nav = R * a_body; const double dt22 = 0.5 * dt * dt; @@ -79,7 +79,7 @@ Vector9 TangentPreintegration::UpdatePreintegrated(const Vector3& a_body, if (A) { // Exact derivative of R*a with respect to theta: - const Matrix3 a_nav_H_theta = R.matrix() * skewSymmetric(-a_body) * local.dexp(); + const Matrix3 a_nav_H_theta = R.matrix() * skewSymmetric(-a_body) * local.rightJacobian(); A->setIdentity(); A->block<3, 3>(0, 0).noalias() += w_tangent_H_theta * dt; // theta diff --git a/gtsam/symbolic/doc/SymbolicBayesNet.ipynb b/gtsam/symbolic/doc/SymbolicBayesNet.ipynb new file mode 100644 index 000000000..49d6d4b43 --- /dev/null +++ b/gtsam/symbolic/doc/SymbolicBayesNet.ipynb @@ -0,0 +1,231 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# SymbolicBayesNet" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "A `SymbolicBayesNet` is a directed acyclic graph (DAG) composed of `SymbolicConditional` objects. It represents the structure of a factorized probability distribution P(X) = Π P(Xi | Parents(Xi)) purely in terms of variable connectivity.\n", + "\n", + "It is typically the result of running sequential variable elimination on a `SymbolicFactorGraph`." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "\"Open" + ] + }, + { + "cell_type": "code", + "execution_count": 13, + "metadata": { + "tags": [ + "remove-cell" + ] + }, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Note: you may need to restart the kernel to use updated packages.\n" + ] + } + ], + "source": [ + "%pip install --quiet gtsam-develop" + ] + }, + { + "cell_type": "code", + "execution_count": 14, + "metadata": {}, + "outputs": [], + "source": [ + "from gtsam import SymbolicConditional, SymbolicFactorGraph, Ordering\n", + "from gtsam.symbol_shorthand import X, L\n", + "import graphviz" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Creating a SymbolicBayesNet\n", + "\n", + "SymbolicBayesNets are usually created by eliminating a [SymbolicFactorGraph](SymbolicFactorGraph.ipynb). But you can also build them directly:" + ] + }, + { + "cell_type": "code", + "execution_count": 15, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Directly Built Symbolic Bayes Net:\n", + " \n", + "size: 5\n", + "conditional 0: P( l1 | x0)\n", + "conditional 1: P( x0 | x1)\n", + "conditional 2: P( l2 | x1)\n", + "conditional 3: P( x1 | x2)\n", + "conditional 4: P( x2)\n" + ] + } + ], + "source": [ + "from gtsam import SymbolicBayesNet\n", + "\n", + "# Create a new Bayes Net\n", + "symbolic_bayes_net = SymbolicBayesNet()\n", + "\n", + "# Add conditionals directly\n", + "symbolic_bayes_net.push_back(SymbolicConditional(L(1), X(0))) # P(l1 | x0)\n", + "symbolic_bayes_net.push_back(SymbolicConditional(X(0), X(1))) # P(x0 | x1)\n", + "symbolic_bayes_net.push_back(SymbolicConditional(L(2), X(1))) # P(l2 | x1)\n", + "symbolic_bayes_net.push_back(SymbolicConditional(X(1), X(2))) # P(x1 | x2)\n", + "symbolic_bayes_net.push_back(SymbolicConditional(X(2))) # P(x2)\n", + "\n", + "symbolic_bayes_net.print(\"Directly Built Symbolic Bayes Net:\\n\")" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Accessing Conditionals and Visualization" + ] + }, + { + "cell_type": "code", + "execution_count": 16, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Conditional at index 1: P( x0 | x1)\n" + ] + }, + { + "data": { + "image/svg+xml": [ + "\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "var7782220156096217089\n", + "\n", + "l1\n", + "\n", + "\n", + "\n", + "var7782220156096217090\n", + "\n", + "l2\n", + "\n", + "\n", + "\n", + "var8646911284551352320\n", + "\n", + "x0\n", + "\n", + "\n", + "\n", + "var8646911284551352320->var7782220156096217089\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "var8646911284551352321\n", + "\n", + "x1\n", + "\n", + "\n", + "\n", + "var8646911284551352321->var7782220156096217090\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "var8646911284551352321->var8646911284551352320\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "var8646911284551352322\n", + "\n", + "x2\n", + "\n", + "\n", + "\n", + "var8646911284551352322->var8646911284551352321\n", + "\n", + "\n", + "\n", + "\n", + "\n" + ], + "text/plain": [ + "" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "# Access a conditional by index\n", + "conditional_1 = bayes_net.at(1) # P(x0 | l1)\n", + "conditional_1.print(\"Conditional at index 1: \")\n", + "\n", + "# Visualize the Bayes Net structure\n", + "display(graphviz.Source(bayes_net.dot()))" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "py312", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.12.6" + } + }, + "nbformat": 4, + "nbformat_minor": 4 +} diff --git a/gtsam/symbolic/doc/SymbolicBayesTree.ipynb b/gtsam/symbolic/doc/SymbolicBayesTree.ipynb new file mode 100644 index 000000000..c6c7aea55 --- /dev/null +++ b/gtsam/symbolic/doc/SymbolicBayesTree.ipynb @@ -0,0 +1,325 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# SymbolicBayesTree" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "A `SymbolicBayesTree` is a tree structure where each node (`SymbolicBayesTreeClique`) represents a clique of variables that were eliminated together during multifrontal elimination. Unlike a `SymbolicJunctionTree` which stores factors, a `SymbolicBayesTree` stores the resulting `SymbolicConditional` for each clique.\n", + "\n", + "It represents the factored structure $P(X) = Π P(C_j | S_j)$, where $C_j$ are the frontal variables of clique $j$ and $S_j$ are its separator variables (parents in the Bayes Tree). This structure is computationally advantageous for inference, especially for calculating marginals or performing incremental updates (like in iSAM)." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "\"Open" + ] + }, + { + "cell_type": "code", + "execution_count": 1, + "metadata": { + "tags": [ + "remove-cell" + ] + }, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Note: you may need to restart the kernel to use updated packages.\n" + ] + } + ], + "source": [ + "%pip install --quiet gtsam-develop" + ] + }, + { + "cell_type": "code", + "execution_count": 1, + "metadata": {}, + "outputs": [], + "source": [ + "from gtsam import SymbolicFactorGraph, Ordering\n", + "from gtsam.symbol_shorthand import X, L\n", + "import graphviz # For visualization" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Creating a SymbolicBayesTree\n", + "\n", + "A Bayes tree is typically created by eliminating a `SymbolicFactorGraph` using the multifrontal method." + ] + }, + { + "cell_type": "code", + "execution_count": 20, + "metadata": {}, + "outputs": [], + "source": [ + "# Create a factor graph from a GTSFM problem\n", + "graph = SymbolicFactorGraph()\n", + "\n", + "edges = [(2, 4), (2, 5), (2, 27), (4, 6), (5, 6), (5, 7), (5, 8), (5, 9), (6, 7), (6, 8), (6, 9), \n", + " (7, 8), (7, 9), (8, 9), (9, 12), (9, 24), (9, 28), (10, 12), (10, 29), (20, 21), (20, 22), \n", + " (20, 23), (20, 24), (21, 22), (21, 23), (21, 24), (22, 23), (22, 24), (23, 24), (25, 26), \n", + " (25, 27), (25, 28), (25, 29), (26, 27), (26, 28), (26, 29), (27, 28), (27, 29), (28, 29)]\n", + "\n", + "for i,j in edges:\n", + " graph.push_factor(X(i), X(j))\n", + "\n", + "# Define an elimination ordering\n", + "ordering = Ordering.MetisSymbolicFactorGraph(graph) # Use METIS for this example\n", + "\n", + "# Eliminate using Multifrontal method\n", + "bayes_tree = graph.eliminateMultifrontal(ordering)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Visualization and Properties\n", + "\n", + "The Bayes tree structure can be visualized, and we can query its properties." + ] + }, + { + "cell_type": "code", + "execution_count": 21, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "\n", + "Bayes Tree size (number of cliques): 8\n", + "Is the Bayes Tree empty? False\n" + ] + } + ], + "source": [ + "print(f\"\\nBayes Tree size (number of cliques): {bayes_tree.size()}\")\n", + "print(f\"Is the Bayes Tree empty? {bayes_tree.empty()}\")" + ] + }, + { + "cell_type": "code", + "execution_count": 22, + "metadata": {}, + "outputs": [ + { + "data": { + "image/svg+xml": [ + "\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "G\n", + "\n", + "\n", + "\n", + "20\n", + "\n", + "x28, x25, x26, x9, x29, x27\n", + "\n", + "\n", + "\n", + "21\n", + "\n", + "x5, x4 : x9, x27\n", + "\n", + "\n", + "\n", + "20->21\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "25\n", + "\n", + "x12 : x9, x29\n", + "\n", + "\n", + "\n", + "20->25\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "27\n", + "\n", + "x24, x23, x22, x21, x20 : x9\n", + "\n", + "\n", + "\n", + "20->27\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "22\n", + "\n", + "x2 : x4, x5, x27\n", + "\n", + "\n", + "\n", + "21->22\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "23\n", + "\n", + "x6 : x4, x5, x9\n", + "\n", + "\n", + "\n", + "21->23\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "24\n", + "\n", + "x8, x7 : x5, x6, x9\n", + "\n", + "\n", + "\n", + "23->24\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "26\n", + "\n", + "x10 : x12, x29\n", + "\n", + "\n", + "\n", + "25->26\n", + "\n", + "\n", + "\n", + "\n", + "\n" + ], + "text/plain": [ + "" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "# Visualize the Bayes tree using graphviz\n", + "display(graphviz.Source(bayes_tree.dot()))" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Traversing a Bayes Tree" + ] + }, + { + "cell_type": "code", + "execution_count": 23, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Number of roots: 1\n", + "\n", + "Clique:\n", + " P( x28 x25 x26 x9 x29 x27)\n", + "\n", + "Clique:\n", + " P( x5 x4 | x9 x27)\n", + "\n", + "Clique:\n", + " P( x2 | x4 x5 x27)\n", + "\n", + "Clique:\n", + " P( x6 | x4 x5 x9)\n", + "\n", + "Clique:\n", + " P( x8 x7 | x5 x6 x9)\n", + "\n", + "Clique:\n", + " P( x12 | x9 x29)\n", + "\n", + "Clique:\n", + " P( x10 | x12 x29)\n", + "\n", + "Clique:\n", + " P( x24 x23 x22 x21 x20 | x9)\n" + ] + } + ], + "source": [ + "roots = bayes_tree.roots()\n", + "print(f\"Number of roots: {len(roots)}\")\n", + "\n", + "def traverse_clique(clique):\n", + " if clique:\n", + " clique.print(\"\\nClique:\\n\")\n", + " for j in range(clique.nrChildren()):\n", + " traverse_clique(clique[j])\n", + "\n", + "for root in roots:\n", + " traverse_clique(root)" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "py312", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.12.6" + } + }, + "nbformat": 4, + "nbformat_minor": 4 +} diff --git a/gtsam/symbolic/doc/SymbolicBayesTreeClique.ipynb b/gtsam/symbolic/doc/SymbolicBayesTreeClique.ipynb new file mode 100644 index 000000000..ba3ed1a8d --- /dev/null +++ b/gtsam/symbolic/doc/SymbolicBayesTreeClique.ipynb @@ -0,0 +1,262 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# SymbolicBayesTreeClique" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "A `SymbolicBayesTreeClique` represents a single node within a `SymbolicBayesTree`. Each clique corresponds to a set of variables (frontal variables) that were eliminated together during the multifrontal elimination process.\n", + "\n", + "Key aspects of a clique:\n", + "* **Conditional:** It stores the `SymbolicConditional` P(Frontals | Parents/Separator) that results from eliminating the frontal variables.\n", + "* **Tree Structure:** It maintains pointers to its parent and children cliques within the Bayes Tree, defining the tree's topology.\n", + "* **Frontal and Separator Variables:** Implicitly defines the frontal variables (eliminated in this clique) and separator variables (parents in the Bayes Tree, connecting it to its parent clique).\n", + "\n", + "Users typically interact with the `SymbolicBayesTree` as a whole, but understanding the clique structure is helpful for comprehending how the Bayes Tree represents the factored distribution and facilitates efficient inference." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "\"Open" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": { + "tags": [ + "remove-cell" + ] + }, + "outputs": [], + "source": [ + "%pip install --quiet gtsam-develop" + ] + }, + { + "cell_type": "code", + "execution_count": 11, + "metadata": {}, + "outputs": [], + "source": [ + "from gtsam import SymbolicFactorGraph, Ordering\n", + "# SymbolicBayesTreeClique is accessed *through* a SymbolicBayesTree\n", + "from gtsam.symbol_shorthand import X, L\n", + "import graphviz" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Accessing and Inspecting Cliques\n", + "\n", + "Cliques are obtained by first creating a `SymbolicBayesTree` (usually via elimination) and then accessing its nodes." + ] + }, + { + "cell_type": "code", + "execution_count": 16, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Bayes Tree has 4 cliques.\n", + "Number of roots: 1\n" + ] + }, + { + "data": { + "image/svg+xml": [ + "\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "G\n", + "\n", + "\n", + "\n", + "6\n", + "\n", + "x1, x2\n", + "\n", + "\n", + "\n", + "7\n", + "\n", + "x0 : x1\n", + "\n", + "\n", + "\n", + "6->7\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "9\n", + "\n", + "l2 : x1\n", + "\n", + "\n", + "\n", + "6->9\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "8\n", + "\n", + "l1 : x0\n", + "\n", + "\n", + "\n", + "7->8\n", + "\n", + "\n", + "\n", + "\n", + "\n" + ], + "text/plain": [ + "" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "# Create a factor graph\n", + "graph = SymbolicFactorGraph()\n", + "graph.push_factor(X(0))\n", + "graph.push_factor(X(0), X(1))\n", + "graph.push_factor(X(1), X(2))\n", + "graph.push_factor(X(0), L(1))\n", + "graph.push_factor(X(1), L(2))\n", + "\n", + "# Eliminate to get a Bayes Tree\n", + "ordering = Ordering.ColamdSymbolicFactorGraph(graph)\n", + "bayes_tree = graph.eliminateMultifrontal(ordering)\n", + "\n", + "print(f\"Bayes Tree has {bayes_tree.size()} cliques.\")\n", + "\n", + "roots = bayes_tree.roots()\n", + "print(f\"Number of roots: {len(roots)}\")\n", + "\n", + "# Visualize the Bayes tree using graphviz\n", + "display(graphviz.Source(bayes_tree.dot()))" + ] + }, + { + "cell_type": "code", + "execution_count": 17, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "\n", + "Inspecting Clique 0:\n", + " Clique Structure: P( x1 x2)\n", + " Associated Conditional: P( P( x1 x2)\n", + " Is Root? True\n", + " Parent Clique is None (likely a root clique).\n", + " Number of Children: 2\n", + "\n", + "Inspecting Clique 0:\n", + " Clique Structure: P( x0 | x1)\n", + " Associated Conditional: P( P( x0 | x1)\n", + " Is Root? False\n", + " Parent Clique exists.\n", + " Number of Children: 1\n", + "\n", + "Inspecting Clique 0:\n", + " Clique Structure: P( l1 | x0)\n", + " Associated Conditional: P( P( l1 | x0)\n", + " Is Root? False\n", + " Parent Clique exists.\n", + " Number of Children: 0\n", + "\n", + "Inspecting Clique 0:\n", + " Clique Structure: P( l2 | x1)\n", + " Associated Conditional: P( P( l2 | x1)\n", + " Is Root? False\n", + " Parent Clique exists.\n", + " Number of Children: 0\n" + ] + } + ], + "source": [ + "def inspect(clique):\n", + " print(\"\\nInspecting Clique 0:\")\n", + " clique.print(\" Clique Structure: \")\n", + " \n", + " # Get the conditional stored in the clique\n", + " conditional = clique.conditional()\n", + " if conditional:\n", + " conditional.print(\" Associated Conditional: P(\")\n", + " else:\n", + " print(\" Clique has no associated conditional (might be empty root)\")\n", + " \n", + " # Check properties\n", + " print(f\" Is Root? {clique.isRoot()}\")\n", + " # Accessing parent/children is possible in C++ but might be less direct or typical in Python wrapper usage\n", + " # Parent clique (careful, might be null for root)\n", + " parent_clique = clique.parent() \n", + " if parent_clique:\n", + " print(\" Parent Clique exists.\")\n", + " else:\n", + " print(\" Parent Clique is None (likely a root clique).\")\n", + " \n", + " print(f\" Number of Children: {clique.nrChildren()}\") # Example if method existed\n", + "\n", + "def traverse_clique(clique):\n", + " inspect(clique)\n", + " for j in range(clique.nrChildren()):\n", + " traverse_clique(clique[j])\n", + "\n", + "for root in roots:\n", + " traverse_clique(root)" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "py312", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.12.6" + } + }, + "nbformat": 4, + "nbformat_minor": 4 +} diff --git a/gtsam/symbolic/doc/SymbolicConditional.ipynb b/gtsam/symbolic/doc/SymbolicConditional.ipynb new file mode 100644 index 000000000..e43881ee0 --- /dev/null +++ b/gtsam/symbolic/doc/SymbolicConditional.ipynb @@ -0,0 +1,142 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# SymbolicConditional" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "A `SymbolicConditional` represents a conditional probability distribution P(Frontals | Parents) in purely symbolic form. It only stores the keys of the frontal variables and the parent variables, without any associated numerical probability function.\n", + "\n", + "`SymbolicConditional` objects are typically produced as the result of symbolic elimination on a `SymbolicFactorGraph`. A collection of these forms a `SymbolicBayesNet`." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "\"Open" + ] + }, + { + "cell_type": "code", + "execution_count": 1, + "metadata": { + "tags": [ + "remove-cell" + ] + }, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Note: you may need to restart the kernel to use updated packages.\n" + ] + } + ], + "source": [ + "%pip install --quiet gtsam-develop" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "from gtsam import SymbolicConditional\n", + "from gtsam.symbol_shorthand import X, L" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Creating SymbolicConditionals\n", + "\n", + "Conditionals specify frontal (conditioned) variables and parent variables." + ] + }, + { + "cell_type": "code", + "execution_count": 3, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "P(X(0)): P( x0)\n", + " Nr Frontals: 1, Nr Parents: 0\n", + "\n", + "P(X(1) | X(0)): P( x1 | x0)\n", + " Nr Frontals: 1, Nr Parents: 1\n", + "\n", + "P(X(2) | X(0), X(1)): P( x2 | x0 x1)\n", + " Nr Frontals: 1, Nr Parents: 2\n", + "\n", + "P(L(1) | X(0), X(1)): P( l1 | x0 x1)\n", + " Nr Frontals: 1, Nr Parents: 2\n", + "\n", + "P(X(2), L(1) | X(0), X(1)): P( x2 l1 | x0 x1)\n", + " Nr Frontals: 2, Nr Parents: 2\n" + ] + } + ], + "source": [ + "# P(X(0))\n", + "c0 = SymbolicConditional(X(0))\n", + "c0.print(\"P(X(0)): \")\n", + "print(f\" Nr Frontals: {c0.nrFrontals()}, Nr Parents: {c0.nrParents()}\\n\")\n", + "\n", + "# P(X(1) | X(0))\n", + "c1 = SymbolicConditional(X(1), X(0))\n", + "c1.print(\"P(X(1) | X(0)): \")\n", + "print(f\" Nr Frontals: {c1.nrFrontals()}, Nr Parents: {c1.nrParents()}\\n\")\n", + "\n", + "# P(X(2) | X(0), X(1))\n", + "c2 = SymbolicConditional(X(2), X(0), X(1))\n", + "c2.print(\"P(X(2) | X(0), X(1)): \")\n", + "print(f\" Nr Frontals: {c2.nrFrontals()}, Nr Parents: {c2.nrParents()}\\n\")\n", + "\n", + "# P(L(1) | X(0), X(1))\n", + "c3 = SymbolicConditional(L(1), X(0), X(1))\n", + "c3.print(\"P(L(1) | X(0), X(1)): \")\n", + "print(f\" Nr Frontals: {c3.nrFrontals()}, Nr Parents: {c3.nrParents()}\\n\")\n", + "\n", + "# Create from keys and number of frontals, e.g. P(X(2), L(1) | X(0), X(1))\n", + "# Keys = [Frontals..., Parents...]\n", + "c4 = SymbolicConditional.FromKeys([X(2), L(1), X(0), X(1)], 2)\n", + "c4.print(\"P(X(2), L(1) | X(0), X(1)): \")\n", + "print(f\" Nr Frontals: {c4.nrFrontals()}, Nr Parents: {c4.nrParents()}\")" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "py312", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.12.6" + } + }, + "nbformat": 4, + "nbformat_minor": 4 +} diff --git a/gtsam/symbolic/doc/SymbolicEliminationTree.ipynb b/gtsam/symbolic/doc/SymbolicEliminationTree.ipynb new file mode 100644 index 000000000..ae068282d --- /dev/null +++ b/gtsam/symbolic/doc/SymbolicEliminationTree.ipynb @@ -0,0 +1,138 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# SymbolicEliminationTree" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "A `SymbolicEliminationTree` represents the computational structure used in variable elimination, particularly in sparse Cholesky or QR factorization. Each node in the tree corresponds to the elimination of a single variable.\n", + "\n", + "The tree structure reveals dependencies: the elimination of a variable (node) depends on the results from its children in the tree. The root of the tree corresponds to the last variable eliminated. This structure is closely related to the resulting Bayes net or Bayes tree." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "\"Open" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": { + "tags": [ + "remove-cell" + ] + }, + "outputs": [], + "source": [ + "%pip install --quiet gtsam-develop" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "from gtsam import SymbolicEliminationTree, SymbolicFactorGraph, Ordering\n", + "from gtsam.symbol_shorthand import X, L" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Creating a SymbolicEliminationTree\n", + "\n", + "An elimination tree is constructed from a `SymbolicFactorGraph` and an `Ordering`." + ] + }, + { + "cell_type": "code", + "execution_count": 4, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Symbolic Elimination Tree:\n", + "-(x2)\n", + "Symbolic Elimination Tree:\n", + "| -(x1)\n", + "Symbolic Elimination Tree:\n", + "| - x1 x2\n", + "Symbolic Elimination Tree:\n", + "| | -(x0)\n", + "Symbolic Elimination Tree:\n", + "| | - x0\n", + "Symbolic Elimination Tree:\n", + "| | - x0 x1\n", + "Symbolic Elimination Tree:\n", + "| | | -(l1)\n", + "Symbolic Elimination Tree:\n", + "| | | - x0 l1\n", + "Symbolic Elimination Tree:\n", + "| | -(l2)\n", + "Symbolic Elimination Tree:\n", + "| | - x1 l2\n" + ] + } + ], + "source": [ + "# Create a factor graph\n", + "graph = SymbolicFactorGraph()\n", + "graph.push_factor(X(0))\n", + "graph.push_factor(X(0), X(1))\n", + "graph.push_factor(X(1), X(2))\n", + "graph.push_factor(X(0), L(1))\n", + "graph.push_factor(X(1), L(2))\n", + "\n", + "# Define an elimination ordering\n", + "ordering = Ordering([L(1), L(2), X(0), X(1), X(2)]) # Eliminate L(1) first, then X(0), X(1), X(2) last\n", + "\n", + "# Construct the elimination tree\n", + "elimination_tree = SymbolicEliminationTree(graph, ordering)\n", + "\n", + "# Print the tree structure (text representation)\n", + "elimination_tree.print(\"Symbolic Elimination Tree:\\n\")" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "*(Note: Direct visualization of the elimination tree structure isn't available via a simple `.dot()` method like factor graphs or Bayes nets/trees in the Python wrapper, but the print output shows the parent-child relationships.)*" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "py312", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.12.6" + } + }, + "nbformat": 4, + "nbformat_minor": 4 +} diff --git a/gtsam/symbolic/doc/SymbolicFactor.ipynb b/gtsam/symbolic/doc/SymbolicFactor.ipynb new file mode 100644 index 000000000..06141920b --- /dev/null +++ b/gtsam/symbolic/doc/SymbolicFactor.ipynb @@ -0,0 +1,131 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# SymbolicFactor" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "A `SymbolicFactor` represents the connectivity (topology) between variables in a factor graph without any specific numerical function associated with it. It's primarily to *illustrate* symbolic elimination. Internally, GTSAM does analyze the structure of other factor graph types without explicitly converting to a symbolic factor graph.\n", + "\n", + "It inherits from `gtsam.Factor` and stores the keys (indices) of the variables it connects." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "\"Open" + ] + }, + { + "cell_type": "code", + "execution_count": 1, + "metadata": { + "tags": [ + "remove-cell" + ] + }, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Note: you may need to restart the kernel to use updated packages.\n" + ] + } + ], + "source": [ + "%pip install --quiet gtsam-develop" + ] + }, + { + "cell_type": "code", + "execution_count": 2, + "metadata": {}, + "outputs": [], + "source": [ + "import gtsam\n", + "from gtsam import SymbolicFactor\n", + "from gtsam.symbol_shorthand import X\n", + "\n", + "# Example Keys\n", + "x0, x1, x2 = X(0), X(1), X(2)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Creating SymbolicFactors\n", + "\n", + "SymbolicFactors can be created by specifying the keys they involve." + ] + }, + { + "cell_type": "code", + "execution_count": 3, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Unary Factor f0: \n", + " x0\n", + "Binary Factor f1: \n", + " x0 x1\n", + "Ternary Factor f2: \n", + " x1 x2 x0\n", + "Factor f3 from KeyVector: \n", + " x0 x1 x2\n" + ] + } + ], + "source": [ + "# Unary factor\n", + "f0 = SymbolicFactor(x0)\n", + "f0.print(\"Unary Factor f0: \\n\")\n", + "\n", + "# Binary factor\n", + "f1 = SymbolicFactor(x0, x1)\n", + "f1.print(\"Binary Factor f1: \\n\")\n", + "\n", + "# Ternary factor\n", + "f2 = SymbolicFactor(x1, x2, x0)\n", + "f2.print(\"Ternary Factor f2: \\n\")\n", + "\n", + "# From a list of keys\n", + "keys = gtsam.KeyVector([x0, x1, x2])\n", + "f3 = SymbolicFactor.FromKeys(keys)\n", + "f3.print(\"Factor f3 from KeyVector: \\n\")" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "py312", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.12.6" + } + }, + "nbformat": 4, + "nbformat_minor": 4 +} diff --git a/gtsam/symbolic/doc/SymbolicFactorGraph.ipynb b/gtsam/symbolic/doc/SymbolicFactorGraph.ipynb new file mode 100644 index 000000000..10c90e321 --- /dev/null +++ b/gtsam/symbolic/doc/SymbolicFactorGraph.ipynb @@ -0,0 +1,479 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# SymbolicFactorGraph" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "A `SymbolicFactorGraph` is a factor graph consisting purely of `SymbolicFactor` objects. It represents the structure or topology of a probabilistic graphical model (like a Markov Random Field) without the numerical details.\n", + "\n", + "It's primarily used to *illustrate* symbolic elimination, which determines the structure of the resulting Bayes net or Bayes tree and finds an efficient variable elimination ordering (e.g., using COLAMD or METIS)." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "\"Open" + ] + }, + { + "cell_type": "code", + "execution_count": 1, + "metadata": { + "tags": [ + "remove-cell" + ] + }, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Note: you may need to restart the kernel to use updated packages.\n" + ] + } + ], + "source": [ + "%pip install --quiet gtsam-develop" + ] + }, + { + "cell_type": "code", + "execution_count": 13, + "metadata": {}, + "outputs": [], + "source": [ + "from gtsam import SymbolicFactorGraph, Ordering\n", + "from gtsam.symbol_shorthand import X, L\n", + "import graphviz" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Creating and Manipulating Symbolic Factor Graphs" + ] + }, + { + "cell_type": "code", + "execution_count": 12, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Symbolic Factor Graph:\n", + " \n", + "size: 5\n", + "factor 0: x0\n", + "factor 1: x0 x1\n", + "factor 2: x1 x2\n", + "factor 3: x0 l1\n", + "factor 4: x1 l2\n" + ] + }, + { + "data": { + "image/svg+xml": [ + "\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "var7782220156096217089\n", + "\n", + "l1\n", + "\n", + "\n", + "\n", + "factor3\n", + "\n", + "\n", + "\n", + "\n", + "var7782220156096217089--factor3\n", + "\n", + "\n", + "\n", + "\n", + "var7782220156096217090\n", + "\n", + "l2\n", + "\n", + "\n", + "\n", + "factor4\n", + "\n", + "\n", + "\n", + "\n", + "var7782220156096217090--factor4\n", + "\n", + "\n", + "\n", + "\n", + "var8646911284551352320\n", + "\n", + "x0\n", + "\n", + "\n", + "\n", + "factor0\n", + "\n", + "\n", + "\n", + "\n", + "var8646911284551352320--factor0\n", + "\n", + "\n", + "\n", + "\n", + "factor1\n", + "\n", + "\n", + "\n", + "\n", + "var8646911284551352320--factor1\n", + "\n", + "\n", + "\n", + "\n", + "var8646911284551352320--factor3\n", + "\n", + "\n", + "\n", + "\n", + "var8646911284551352321\n", + "\n", + "x1\n", + "\n", + "\n", + "\n", + "var8646911284551352321--factor1\n", + "\n", + "\n", + "\n", + "\n", + "factor2\n", + "\n", + "\n", + "\n", + "\n", + "var8646911284551352321--factor2\n", + "\n", + "\n", + "\n", + "\n", + "var8646911284551352321--factor4\n", + "\n", + "\n", + "\n", + "\n", + "var8646911284551352322\n", + "\n", + "x2\n", + "\n", + "\n", + "\n", + "var8646911284551352322--factor2\n", + "\n", + "\n", + "\n", + "\n" + ], + "text/plain": [ + "" + ] + }, + "execution_count": 12, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "# Create an empty graph\n", + "graph = SymbolicFactorGraph()\n", + "\n", + "# Add factors (using convenience methods)\n", + "graph.push_factor(X(0)) # Unary\n", + "graph.push_factor(X(0), X(1))\n", + "graph.push_factor(X(1), X(2))\n", + "graph.push_factor(X(0), L(1))\n", + "graph.push_factor(X(1), L(2))\n", + "\n", + "# Print the graph structure\n", + "graph.print(\"Symbolic Factor Graph:\\n\")\n", + "\n", + "# Visualize the graph using Graphviz\n", + "graphviz.Source(graph.dot())" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Symbolic Elimination\n", + "\n", + "We can perform symbolic elimination to get the structure of the resulting Bayes net or Bayes tree." + ] + }, + { + "cell_type": "code", + "execution_count": 16, + "metadata": {}, + "outputs": [], + "source": [ + "# Define an elimination ordering (can also be computed automatically)\n", + "ordering = Ordering([L(1), L(2), X(0), X(1), X(2)])" + ] + }, + { + "cell_type": "code", + "execution_count": 18, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "\n", + "Resulting Symbolic Bayes Net:\n", + " \n", + "size: 5\n", + "conditional 0: P( l1 | x0)\n", + "conditional 1: P( x0 | x1)\n", + "conditional 2: P( l2 | x1)\n", + "conditional 3: P( x1 | x2)\n", + "conditional 4: P( x2)\n" + ] + }, + { + "data": { + "image/svg+xml": [ + "\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "var7782220156096217089\n", + "\n", + "l1\n", + "\n", + "\n", + "\n", + "var7782220156096217090\n", + "\n", + "l2\n", + "\n", + "\n", + "\n", + "var8646911284551352320\n", + "\n", + "x0\n", + "\n", + "\n", + "\n", + "var8646911284551352320->var7782220156096217089\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "var8646911284551352321\n", + "\n", + "x1\n", + "\n", + "\n", + "\n", + "var8646911284551352321->var7782220156096217090\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "var8646911284551352321->var8646911284551352320\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "var8646911284551352322\n", + "\n", + "x2\n", + "\n", + "\n", + "\n", + "var8646911284551352322->var8646911284551352321\n", + "\n", + "\n", + "\n", + "\n", + "\n" + ], + "text/plain": [ + "" + ] + }, + "execution_count": 18, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "# Eliminate sequentially to get a Bayes Net structure\n", + "bayes_net = graph.eliminateSequential(ordering)\n", + "bayes_net.print(\"\\nResulting Symbolic Bayes Net:\\n\")\n", + "\n", + "# Visualize the Bayes Net using Graphviz\n", + "graphviz.Source(bayes_net.dot())" + ] + }, + { + "cell_type": "code", + "execution_count": 19, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "\n", + "Resulting Symbolic Bayes Tree:\n", + ": cliques: 4, variables: 5\n", + "\n", + "Resulting Symbolic Bayes Tree:\n", + "- P( x1 x2)\n", + "\n", + "Resulting Symbolic Bayes Tree:\n", + "| - P( x0 | x1)\n", + "\n", + "Resulting Symbolic Bayes Tree:\n", + "| | - P( l1 | x0)\n", + "\n", + "Resulting Symbolic Bayes Tree:\n", + "| - P( l2 | x1)\n" + ] + }, + { + "data": { + "image/svg+xml": [ + "\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "G\n", + "\n", + "\n", + "\n", + "0\n", + "\n", + "x1, x2\n", + "\n", + "\n", + "\n", + "1\n", + "\n", + "x0 : x1\n", + "\n", + "\n", + "\n", + "0->1\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "3\n", + "\n", + "l2 : x1\n", + "\n", + "\n", + "\n", + "0->3\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "2\n", + "\n", + "l1 : x0\n", + "\n", + "\n", + "\n", + "1->2\n", + "\n", + "\n", + "\n", + "\n", + "\n" + ], + "text/plain": [ + "" + ] + }, + "execution_count": 19, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "# Eliminate using Multifrontal method to get a Bayes Tree structure\n", + "bayes_tree = graph.eliminateMultifrontal(ordering)\n", + "bayes_tree.print(\"\\nResulting Symbolic Bayes Tree:\\n\")\n", + "\n", + "# Visualize the Bayes Tree using Graphviz\n", + "graphviz.Source(bayes_tree.dot())" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "py312", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.12.6" + } + }, + "nbformat": 4, + "nbformat_minor": 4 +} diff --git a/gtsam/symbolic/doc/SymbolicJunctionTree.ipynb b/gtsam/symbolic/doc/SymbolicJunctionTree.ipynb new file mode 100644 index 000000000..3f600b42b --- /dev/null +++ b/gtsam/symbolic/doc/SymbolicJunctionTree.ipynb @@ -0,0 +1,133 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# SymbolicJunctionTree" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "A `SymbolicJunctionTree` (often used interchangeably with Clique Tree in GTSAM documentation) is a data structure used in multifrontal variable elimination. It's derived from an `EliminationTree`.\n", + "\n", + "Key differences from an Elimination Tree:\n", + "* **Nodes are Cliques:** Each node in a Junction Tree represents a *clique* (a group of variables eliminated together), not just a single variable.\n", + "* **Stores Factors:** Nodes (`SymbolicCluster` objects) store the symbolic factors associated with the variables in that clique.\n", + "\n", + "The Junction Tree organizes the factors and variables for efficient multifrontal elimination, which processes variables in these larger cliques simultaneously. The result of eliminating a Junction Tree is a `SymbolicBayesTree`." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "\"Open" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": { + "tags": [ + "remove-cell" + ] + }, + "outputs": [], + "source": [ + "%pip install --quiet gtsam-develop" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "from gtsam import SymbolicJunctionTree, SymbolicEliminationTree, SymbolicFactorGraph, Ordering\n", + "from gtsam.symbol_shorthand import X, L" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Creating a SymbolicJunctionTree\n", + "\n", + "A Junction Tree is constructed from a `SymbolicEliminationTree`." + ] + }, + { + "cell_type": "code", + "execution_count": 4, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Symbolic Junction Tree:\n", + "- (6) x1 x2 \n", + "Symbolic Junction Tree:\n", + "| - (6) x0 \n", + "Symbolic Junction Tree:\n", + "| | - (2) l1 \n", + "Symbolic Junction Tree:\n", + "| - (2) l2 \n" + ] + } + ], + "source": [ + "# Create a factor graph\n", + "graph = SymbolicFactorGraph()\n", + "graph.push_factor(X(0))\n", + "graph.push_factor(X(0), X(1))\n", + "graph.push_factor(X(1), X(2))\n", + "graph.push_factor(X(0), L(1))\n", + "graph.push_factor(X(1), L(2))\n", + "\n", + "# Define an elimination ordering\n", + "ordering = Ordering([L(1), L(2), X(0), X(1), X(2)]) \n", + "\n", + "# Construct the elimination tree first\n", + "elimination_tree = SymbolicEliminationTree(graph, ordering)\n", + "\n", + "# Construct the junction tree from the elimination tree\n", + "junction_tree = SymbolicJunctionTree(elimination_tree)\n", + "\n", + "# Print the tree structure (text representation)\n", + "junction_tree.print(\"Symbolic Junction Tree:\\n\")" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "*(Note: The `SymbolicCluster` class represents the nodes within the Junction Tree, containing the factors and frontal/separator keys for that clique. Direct visualization is usually done via the resulting Bayes Tree.)*" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "py312", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.12.6" + } + }, + "nbformat": 4, + "nbformat_minor": 4 +} diff --git a/gtsam/symbolic/symbolic.i b/gtsam/symbolic/symbolic.i index 27cb1b1b8..adf7efba3 100644 --- a/gtsam/symbolic/symbolic.i +++ b/gtsam/symbolic/symbolic.i @@ -185,6 +185,8 @@ class SymbolicBayesTreeClique { const gtsam::SymbolicConditional* conditional() const; bool isRoot() const; gtsam::SymbolicBayesTreeClique* parent() const; + size_t nrChildren() const; + gtsam::SymbolicBayesTreeClique* operator[](size_t j) const; size_t treeSize() const; size_t numCachedSeparatorMarginals() const; void deleteCachedShortcuts(); @@ -204,7 +206,7 @@ class SymbolicBayesTree { // Standard Interface bool empty() const; size_t size() const; - + const SymbolicBayesTree::Roots& roots() const; const gtsam::SymbolicBayesTreeClique* operator[](size_t j) const; void saveGraph(string s, diff --git a/gtsam/symbolic/symbolic.md b/gtsam/symbolic/symbolic.md new file mode 100644 index 000000000..bfae60842 --- /dev/null +++ b/gtsam/symbolic/symbolic.md @@ -0,0 +1,40 @@ +# Symbolic Module + +The `symbolic` module in GTSAM deals with the *structure* of factor graphs and Bayesian networks, independent of the specific numerical types of factors (like Gaussian or discrete). It allows for analyzing graph connectivity, determining optimal variable elimination orders, and understanding the sparsity structure of the resulting inference objects. + +This is crucial for efficient inference, as the symbolic elimination steps determine the computational complexity and memory requirements of the numerical factorization. + +The classes here are used primarily to *illustrate* symbolic elimination. Internally, GTSAM does analyze the structure of other factor graph types without explicitly converting to a symbolic factor graph. + + +## Classes + +Here's an overview of the key classes in the `symbolic` module: + +### Factor Graph + +- **[SymbolicFactor](doc/SymbolicFactor.ipynb)**: Represents the connectivity between a set of variables (keys) in a factor graph, without any specific numerical function associated with it. It defines the hyperedges of the graph. +- **[SymbolicFactorGraph](doc/SymbolicFactorGraph.ipynb)**: A collection of `SymbolicFactor` objects, representing the overall structure of a factor graph. + +### Elimination Products + +These classes represent the results of symbolic variable elimination: + +- **[SymbolicConditional](doc/SymbolicConditional.ipynb)**: Represents the structure of a conditional probability distribution P(Frontals | Parents). It stores the keys of the frontal (conditioned) and parent variables resulting from eliminating one or more variables from a set of factors. +- **[SymbolicBayesNet](doc/SymbolicBayesNet.ipynb)**: A directed acyclic graph composed of `SymbolicConditional` objects, representing the structure of a factorized distribution P(X) = Π P(Xi | Parents(Xi)). Typically results from sequential elimination. +- **[SymbolicBayesTree](doc/SymbolicBayesTree.ipynb)**: A tree structure where each node (`SymbolicBayesTreeClique`) represents a `SymbolicConditional` P(Frontals | Separator). This is the result of multifrontal elimination and is the underlying structure for efficient incremental updates (iSAM) and exact marginal computation. +- **[SymbolicBayesTreeClique](doc/SymbolicBayesTreeClique.ipynb)**: Represents a single clique (node) within a `SymbolicBayesTree`, containing a `SymbolicConditional`. + +### Elimination Structures + +These classes represent intermediate structures used during the elimination process: + +- **[SymbolicEliminationTree](doc/SymbolicEliminationTree.ipynb)**: Represents the dependency structure of sequential variable elimination. Each node corresponds to eliminating a single variable. +- **[SymbolicJunctionTree](doc/SymbolicJunctionTree.ipynb)** (Clique Tree): An intermediate structure used in multifrontal elimination, derived from an elimination tree. Each node (`SymbolicCluster`) represents a clique of variables eliminated together and stores the *factors* associated with that clique. + +**Importance** +Performing symbolic analysis can be used for: +1. Choosing an Optimal Ordering: Finding an ordering that minimizes fill-in (new connections created during elimination) is key to efficient numerical factorization. +2. Predicting Computational Cost: The structure of the Bayes net or Bayes tree determines the complexity of subsequent numerical operations like solving or marginalization. +3. Memory Allocation: Knowing the structure allows for pre-allocation of memory for the numerical factorization. +The symbolic module provides the foundation for GTSAM's efficient inference algorithms. diff --git a/myst.yml b/myst.yml index 80d190996..5fbe34010 100644 --- a/myst.yml +++ b/myst.yml @@ -19,6 +19,9 @@ project: - file: ./gtsam/nonlinear/nonlinear.md children: - pattern: ./gtsam/nonlinear/doc/* + - file: ./gtsam/symbolic/symbolic.md + children: + - pattern: ./gtsam/symbolic/doc/* - file: ./gtsam/navigation/navigation.md children: - pattern: ./gtsam/navigation/doc/*