gtsam 4.1.1
gtsam
gtsam::FitBasis< Basis > Class Template Reference

Detailed Description

template<class Basis>
class gtsam::FitBasis< Basis >

Class that does regression via least squares Example usage: size_t N = 3; auto fit = FitBasis<Chebyshev2>(data_points, noise_model, N); Vector coefficients = fit.parameters();.

where data_points are a map from x to y values indicating a function mapping at specific points, noise_model is the gaussian noise model, and N is the degree of the polynomial basis used to fit the function.

Public Member Functions

 FitBasis (const Sequence &sequence, const SharedNoiseModel &model, size_t N)
 Construct a new FitBasis object. More...
 
Parameters parameters () const
 Return Fourier coefficients.
 

Static Public Member Functions

static NonlinearFactorGraph NonlinearGraph (const Sequence &sequence, const SharedNoiseModel &model, size_t N)
 Create nonlinear FG from Sequence.
 
static GaussianFactorGraph::shared_ptr LinearGraph (const Sequence &sequence, const SharedNoiseModel &model, size_t N)
 Create linear FG from Sequence.
 

Public Types

using Parameters = typename Basis::Parameters
 

Constructor & Destructor Documentation

◆ FitBasis()

template<class Basis >
gtsam::FitBasis< Basis >::FitBasis ( const Sequence sequence,
const SharedNoiseModel model,
size_t  N 
)
inline

Construct a new FitBasis object.

Parameters
sequencemap of x->y values for a function, a.k.a. y = f(x).
modelThe noise model to use.
NThe degree of the polynomial to fit.

The documentation for this class was generated from the following file: