gtsam.Factor
is the abstract base class for all factors in GTSAM, including nonlinear factors, Gaussian factors, discrete factors, and conditionals. It defines the basic interface common to all factors, primarily centered around the set of variables (keys) the factor involves.
You typically do not instantiate gtsam.Factor
directly but rather work with its derived classes like gtsam.NonlinearFactor
, gtsam.JacobianFactor
, gtsam.DiscreteFactor
, etc.
The error
function of a factor is typically related to a probability or likelihood or via the negative log-likelihood:
or equivalently:
where are the variables involved in the factor, is the potential function (proportional to probability or likelihood), and is some constant. Minimizing the error corresponds to maximizing the probability/likelihood represented by the factor.
import gtsam
from gtsam.utils.test_case import GtsamTestCase
# We need a concrete factor type for demonstration
from gtsam import PriorFactorPose2, BetweenFactorPose2, Pose2, Point3
from gtsam import symbol_shorthand
X = symbol_shorthand.X
Basic Interface¶
All factors provide methods to access the keys of the variables they involve.
noise_model = gtsam.noiseModel.Diagonal.Sigmas(Point3(0.1, 0.1, 0.05))
# Create some concrete factors
prior_factor = PriorFactorPose2(X(0), Pose2(0, 0, 0), noise_model)
between_factor = BetweenFactorPose2(X(0), X(1), Pose2(1, 0, 0), noise_model)
# Access keys (methods inherited from gtsam.Factor)
prior_keys = prior_factor.keys()
print(f"Prior factor keys: {prior_keys} ({gtsam.DefaultKeyFormatter(prior_keys[0])})")
print(f"Prior factor size: {prior_factor.size()}")
between_keys = between_factor.keys()
print(f"Between factor keys: {between_keys} ({gtsam.DefaultKeyFormatter(between_keys[0])}, {gtsam.DefaultKeyFormatter(between_keys[1])})")
print(f"Between factor size: {between_factor.size()}")
print(f"Is prior factor empty? {prior_factor.empty()}")
# Factors can be printed
prior_factor.print("Prior Factor: ")
Prior factor keys: [8646911284551352320] (x0)
Prior factor size: 1
Between factor keys: [8646911284551352320, 8646911284551352321] (x0, x1)
Between factor size: 2
Is prior factor empty? False
Prior Factor: PriorFactor on x0
prior mean: (0, 0, 0)
noise model: diagonal sigmas [0.1; 0.1; 0.05];
Error Function¶
A key method for many factor types (especially nonlinear and Gaussian) is error(Values)
. This evaluates the negative log-likelihood of the factor given a specific assignment of variable values. For optimization, the goal is typically to find the Values
that minimize the total error (sum of errors from all factors).
values = gtsam.Values()
values.insert(X(0), Pose2(0, 0, 0))
values.insert(X(1), Pose2(1, 0, 0))
# Evaluate error (example with BetweenFactor)
error1 = between_factor.error(values)
print(f"Error at ground truth: {error1}")
# Change a value and recalculate error
values.update(X(1), Pose2(0, 0, 0))
error2 = between_factor.error(values)
print(f"Error with incorrect x1: {error2:.1f}")
Error at ground truth: 0.0
Error with incorrect x1: 50.0