SmartProjectionParams
is a structure used to configure the behavior of “smart” factors like SmartProjectionFactor
, SmartProjectionPoseFactor
, and SmartStereoFactor
.
These factors implicitly manage the triangulation of a 3D point observed by multiple cameras.
Parameters include:
linearizationMode
: Determines the type of linear factor produced when.linearize()
is called.HESSIAN
(Default): Creates aRegularHessianFactor
by marginalizing out the point.IMPLICIT_SCHUR
: Creates aRegularImplicitSchurFactor
.JACOBIAN_Q
: Creates aJacobianFactorQ
.JACOBIAN_SVD
: Creates aJacobianFactorSVD
.
degeneracyMode
: How to handle cases where triangulation fails or is ill-conditioned.IGNORE_DEGENERACY
(Default): Factor might become ill-conditioned.ZERO_ON_DEGENERACY
: Return a zero-information factor (Hessian/Jacobian) if triangulation fails.HANDLE_INFINITY
: Treat the point as being at infinity (usesUnit3
representation).
triangulation
: Agtsam.TriangulationParameters
struct containing parameters for thetriangulateSafe
function:rankTolerance
: Rank tolerance threshold for SVD during triangulation.enableEPI
: Use Essential matrix check for epipolar inconsistency (only for Point3 landmarks).landmarkDistanceThreshold
: If point distance is greater than this, use point-at-infinity.dynamicOutlierRejectionThreshold
: If non-zero, dynamically rejects measurements based on reprojection error (threshold in sigmas).
retriangulationThreshold
: If the change in camera poses between linearizations exceeds this threshold (Frobenius norm difference), the point is re-triangulated.throwCheirality
/verboseCheirality
: Flags inherited from projection factors to control exception handling when a point is behind a camera.
import gtsam
from gtsam import SmartProjectionParams, LinearizationMode, DegeneracyMode
Creating and Modifying Params¶
# Default parameters
default_params = SmartProjectionParams()
print("Default Parameters:")
default_params.print()
# Custom parameters
custom_params = SmartProjectionParams(
linMode = LinearizationMode.JACOBIAN_Q,
degMode = DegeneracyMode.ZERO_ON_DEGENERACY,
throwCheirality = False,
verboseCheirality = True,
retriangulationTh = 1e-3
)
# Modify triangulation parameters directly
custom_params.setRankTolerance(1e-8)
custom_params.setEnableEPI(False)
custom_params.setDynamicOutlierRejectionThreshold(3.0) # Reject points with reproj error > 3*sigma
print("\nCustom Parameters:")
custom_params.print()
Default Parameters:
linearizationMode: 0
degeneracyMode: 0
rankTolerance = 1
enableEPI = 0
landmarkDistanceThreshold = -1
dynamicOutlierRejectionThreshold = -1
useLOST = 0
noise model
Custom Parameters:
linearizationMode: 2
degeneracyMode: 1
rankTolerance = 1e-08
enableEPI = 0
landmarkDistanceThreshold = -1
dynamicOutlierRejectionThreshold = 1
useLOST = 0
noise model
Usage¶
These SmartProjectionParams
objects are passed to the constructors of smart factors, like SmartProjectionPoseFactor
.
from gtsam import SmartProjectionPoseFactorCal3_S2, Cal3_S2
# Example: Using custom params with a smart factor
noise = gtsam.noiseModel.Isotropic.Sigma(2, 1.0)
K = Cal3_S2(500, 500, 0, 320, 240)
smart_factor = SmartProjectionPoseFactorCal3_S2(noise, K, custom_params)
print("Smart Factor created with custom params:")
smart_factor.print()
Smart Factor created with custom params:
SmartProjectionPoseFactor, z =
SmartProjectionFactor
linearizationMode: 2
triangulationParameters:
rankTolerance = 1e-08
enableEPI = 0
landmarkDistanceThreshold = -1
dynamicOutlierRejectionThreshold = 1
useLOST = 0
noise model
result:
no point, status = 1
SmartFactorBase, z =
keys = { }