Overview¶
VectorEvaluationFactor is a unary factor for vector-valued measurements evaluated from a basis parameter matrix. It enforces to match a measurement vector at a given point.
Key Functionality / API¶
VectorEvaluationFactor(key, z, model, M, N, x)constrains the full vector.Optional interval parameters
a, bscale the basis domain.
C++ Usage Example¶
gtsam::Vector z = (gtsam::Vector(3) << 1.0, 0.0, -0.5).finished();
auto model = gtsam::noiseModel::Isotropic::Sigma(3, 0.1);
size_t M = 3, N = 6;
double x = 0.0;
gtsam::VectorEvaluationFactor<gtsam::Chebyshev2> factor(key, z, model, M, N, x);Python Example¶
import numpy as np
import gtsam
candidates = [n for n in dir(gtsam) if n.startswith("VectorEvaluationFactor")]
print("VectorEvaluationFactor wrappers:")
for name in candidates:
print(" ", name)
cls = None
selected = None
for name in [
"VectorEvaluationFactorChebyshev2",
"VectorEvaluationFactorChebyshev2Basis",
"VectorEvaluationFactorChebyshev1Basis",
"VectorEvaluationFactorFourierBasis",
]:
if hasattr(gtsam, name):
cls = getattr(gtsam, name)
selected = name
if cls is None:
print("No VectorEvaluationFactor wrapper found; skipping execution.")
else:
z = np.array([1.0, 0.0, -0.5])
model = gtsam.noiseModel.Isotropic.Sigma(3, 0.1)
key = gtsam.symbol('c', 0)
factor = cls(key, z, model, 3, 6, 0.0)
print(f"Created {selected} with dim {factor.dim()}")
VectorEvaluationFactor wrappers:
VectorEvaluationFactorChebyshev1Basis
VectorEvaluationFactorChebyshev2
VectorEvaluationFactorChebyshev2Basis
VectorEvaluationFactorFourierBasis
Created VectorEvaluationFactorChebyshev2 with dim 3
Created VectorEvaluationFactorChebyshev2Basis with dim 3
Created VectorEvaluationFactorChebyshev1Basis with dim 3
Created VectorEvaluationFactorFourierBasis with dim 3