Skip to article frontmatterSkip to article content
Site not loading correctly?

This may be due to an incorrect BASE_URL configuration. See the MyST Documentation for reference.

VectorDerivativeFactor

Open In Colab

Overview

VectorDerivativeFactor is a unary factor that enforces a vector measurement of the derivative of a vector-valued basis function at a given point.

Key Functionality / API

  • VectorDerivativeFactor(key, z, model, M, N, x) constrains f(x)\mathbf{f}'(x).

  • Optional interval parameters a, b scale the basis domain.

C++ Usage Example

gtsam::Vector z = (gtsam::Vector(2) << 0.1, -0.1).finished();
auto model = gtsam::noiseModel::Isotropic::Sigma(2, 0.05);
size_t M = 2, N = 6;
double x = 0.0;
gtsam::VectorDerivativeFactor<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("VectorDerivativeFactor")]
print("VectorDerivativeFactor wrappers:")
for name in candidates:
    print("  ", name)

z = np.array([0.1, -0.1])
model = gtsam.noiseModel.Isotropic.Sigma(2, 0.05)
key = gtsam.symbol('c', 0)
factor = gtsam.VectorDerivativeFactorChebyshev2(key, z, model, 2, 6, 0.0)
print("factor:\n", factor)
VectorDerivativeFactor wrappers:
   VectorDerivativeFactorChebyshev1Basis
   VectorDerivativeFactorChebyshev2
   VectorDerivativeFactorChebyshev2Basis
   VectorDerivativeFactorFourierBasis
factor:
   keys = { c0 }
isotropic dim=2 sigma=0.05
FunctorizedFactor(c0)
  measurement: [
	0.1;
	-0.1
]
  noise model sigmas: 0.05 0.05