Overview¶
FitBasis performs least-squares regression to fit a basis function to sample data. It builds a factor graph from samples and solves for basis parameters that best explain the data under a Gaussian noise model.
Key Functionality / API¶
FitBasis(sequence, model, N)constructs and solves the least-squares problem.parameters()returns the fitted parameter vector.NonlinearGraph(...)andLinearGraph(...)expose intermediate graphs.
C++ Usage Example¶
std::map<double, double> samples = {{0.0, 1.0}, {0.5, 0.2}, {1.0, -0.1}};
auto model = gtsam::noiseModel::Isotropic::Sigma(1, 0.1);
size_t N = 5;
gtsam::FitBasis<gtsam::Chebyshev2> fit(samples, model, N);
gtsam::Vector params = fit.parameters();
Python Example¶
import numpy as np
import gtsam
np.set_printoptions(precision=3, suppress=True)
sequence = {0.0: 1.0, 0.5: 0.2, 1.0: -0.1}
model = gtsam.noiseModel.Isotropic.Sigma(1, 0.1)
fit = gtsam.FitBasisFourierBasis(sequence, model, 3)
params = fit.parameters()
print("FitBasisFourierBasis parameters:", params)FitBasisFourierBasis parameters: [ 2.242 -1.242 -1.986]