Overview¶
VectorComponentFactor is a unary factor that constrains a single component of a vector-valued basis function at a given point. It is useful when only one component is observed.
Key Functionality / API¶
VectorComponentFactor(key, z, model, P, N, i, x)constrains componenti.Optional interval parameters
a, bscale the basis domain.
C++ Usage Example¶
auto model = gtsam::noiseModel::Isotropic::Sigma(1, 0.1);
size_t P = 3, N = 6, i = 1;
double x = 0.5;
double z = -0.2;
gtsam::VectorComponentFactor<gtsam::Chebyshev2> factor(key, z, model, P, N, i, x);Python Example¶
import gtsam
candidates = [n for n in dir(gtsam) if n.startswith("VectorComponentFactor")]
print("VectorComponentFactor wrappers:")
for name in candidates:
print(" ", name)
cls = None
selected = None
for name in candidates:
if hasattr(gtsam, name):
cls = getattr(gtsam, name)
selected = name
if cls is None:
print("No VectorComponentFactor wrapper found; skipping execution.")
else:
model = gtsam.noiseModel.Isotropic.Sigma(1, 0.1)
key = gtsam.symbol('c', 0)
factor = cls(key, -0.2, model, 3, 6, 1, 0.5)
print(f"Created {selected} with dim {factor.dim()}")
VectorComponentFactor wrappers:
VectorComponentFactorChebyshev1Basis
VectorComponentFactorChebyshev2
VectorComponentFactorChebyshev2Basis
VectorComponentFactorFourierBasis
Created VectorComponentFactorChebyshev1Basis with dim 1
Created VectorComponentFactorChebyshev2 with dim 1
Created VectorComponentFactorChebyshev2Basis with dim 1
Created VectorComponentFactorFourierBasis with dim 1