update wrapped code
parent
73c950e69a
commit
445ffb3110
|
|
@ -71,44 +71,28 @@ virtual class EvaluationFactor : gtsam::NoiseModelFactor {
|
||||||
double x, double a, double b);
|
double x, double a, double b);
|
||||||
};
|
};
|
||||||
|
|
||||||
template <BASIS, M>
|
template <BASIS = {gtsam::Chebyshev2}>
|
||||||
virtual class VectorEvaluationFactor : gtsam::NoiseModelFactor {
|
virtual class VectorEvaluationFactor : gtsam::NoiseModelFactor {
|
||||||
VectorEvaluationFactor();
|
VectorEvaluationFactor();
|
||||||
VectorEvaluationFactor(gtsam::Key key, const Vector& z,
|
VectorEvaluationFactor(gtsam::Key key, const Vector& z,
|
||||||
const gtsam::noiseModel::Base* model, const size_t N,
|
const gtsam::noiseModel::Base* model, const size_t M,
|
||||||
double x);
|
const size_t N, double x);
|
||||||
VectorEvaluationFactor(gtsam::Key key, const Vector& z,
|
VectorEvaluationFactor(gtsam::Key key, const Vector& z,
|
||||||
const gtsam::noiseModel::Base* model, const size_t N,
|
const gtsam::noiseModel::Base* model, const size_t M,
|
||||||
double x, double a, double b);
|
const size_t N, double x, double a, double b);
|
||||||
};
|
};
|
||||||
|
|
||||||
// TODO(Varun) Better way to support arbitrary dimensions?
|
template <BASIS = {gtsam::Chebyshev2}>
|
||||||
// Especially if users mainly do `pip install gtsam` for the Python wrapper.
|
|
||||||
typedef gtsam::VectorEvaluationFactor<gtsam::Chebyshev2, 3>
|
|
||||||
VectorEvaluationFactorChebyshev2D3;
|
|
||||||
typedef gtsam::VectorEvaluationFactor<gtsam::Chebyshev2, 4>
|
|
||||||
VectorEvaluationFactorChebyshev2D4;
|
|
||||||
typedef gtsam::VectorEvaluationFactor<gtsam::Chebyshev2, 12>
|
|
||||||
VectorEvaluationFactorChebyshev2D12;
|
|
||||||
|
|
||||||
template <BASIS, P>
|
|
||||||
virtual class VectorComponentFactor : gtsam::NoiseModelFactor {
|
virtual class VectorComponentFactor : gtsam::NoiseModelFactor {
|
||||||
VectorComponentFactor();
|
VectorComponentFactor();
|
||||||
VectorComponentFactor(gtsam::Key key, const double z,
|
VectorComponentFactor(gtsam::Key key, const double z,
|
||||||
const gtsam::noiseModel::Base* model, const size_t N,
|
const gtsam::noiseModel::Base* model, const size_t M,
|
||||||
size_t i, double x);
|
const size_t N, size_t i, double x);
|
||||||
VectorComponentFactor(gtsam::Key key, const double z,
|
VectorComponentFactor(gtsam::Key key, const double z,
|
||||||
const gtsam::noiseModel::Base* model, const size_t N,
|
const gtsam::noiseModel::Base* model, const size_t M,
|
||||||
size_t i, double x, double a, double b);
|
const size_t N, size_t i, double x, double a, double b);
|
||||||
};
|
};
|
||||||
|
|
||||||
typedef gtsam::VectorComponentFactor<gtsam::Chebyshev2, 3>
|
|
||||||
VectorComponentFactorChebyshev2D3;
|
|
||||||
typedef gtsam::VectorComponentFactor<gtsam::Chebyshev2, 4>
|
|
||||||
VectorComponentFactorChebyshev2D4;
|
|
||||||
typedef gtsam::VectorComponentFactor<gtsam::Chebyshev2, 12>
|
|
||||||
VectorComponentFactorChebyshev2D12;
|
|
||||||
|
|
||||||
template <BASIS, T>
|
template <BASIS, T>
|
||||||
virtual class ManifoldEvaluationFactor : gtsam::NoiseModelFactor {
|
virtual class ManifoldEvaluationFactor : gtsam::NoiseModelFactor {
|
||||||
ManifoldEvaluationFactor();
|
ManifoldEvaluationFactor();
|
||||||
|
|
@ -127,8 +111,39 @@ typedef gtsam::ManifoldEvaluationFactor<gtsam::Chebyshev2, gtsam::Rot3>
|
||||||
typedef gtsam::ManifoldEvaluationFactor<gtsam::Chebyshev2, gtsam::Pose3>
|
typedef gtsam::ManifoldEvaluationFactor<gtsam::Chebyshev2, gtsam::Pose3>
|
||||||
ManifoldEvaluationFactorChebyshev2Pose3;
|
ManifoldEvaluationFactorChebyshev2Pose3;
|
||||||
|
|
||||||
// TODO(gerry): Add `DerivativeFactor`, `VectorDerivativeFactor`, and
|
template <BASIS = {gtsam::Chebyshev2}>
|
||||||
// `ComponentDerivativeFactor`
|
virtual class DerivativeFactor : gtsam::NoiseModelFactor {
|
||||||
|
DerivativeFactor();
|
||||||
|
DerivativeFactor(gtsam::Key key, const double z,
|
||||||
|
const gtsam::noiseModel::Base* model, const size_t N,
|
||||||
|
double x);
|
||||||
|
DerivativeFactor(gtsam::Key key, const double z,
|
||||||
|
const gtsam::noiseModel::Base* model, const size_t N,
|
||||||
|
double x, double a, double b);
|
||||||
|
};
|
||||||
|
|
||||||
|
template <BASIS = {gtsam::Chebyshev2}>
|
||||||
|
virtual class VectorDerivativeFactor : gtsam::NoiseModelFactor {
|
||||||
|
VectorDerivativeFactor();
|
||||||
|
VectorDerivativeFactor(gtsam::Key key, const Vector& z,
|
||||||
|
const gtsam::noiseModel::Base* model, const size_t M,
|
||||||
|
const size_t N, double x);
|
||||||
|
VectorDerivativeFactor(gtsam::Key key, const Vector& z,
|
||||||
|
const gtsam::noiseModel::Base* model, const size_t M,
|
||||||
|
const size_t N, double x, double a, double b);
|
||||||
|
};
|
||||||
|
|
||||||
|
template <BASIS = {gtsam::Chebyshev2}>
|
||||||
|
virtual class ComponentDerivativeFactor : gtsam::NoiseModelFactor {
|
||||||
|
ComponentDerivativeFactor();
|
||||||
|
ComponentDerivativeFactor(gtsam::Key key, const double z,
|
||||||
|
const gtsam::noiseModel::Base* model,
|
||||||
|
const size_t P, const size_t N, size_t i, double x);
|
||||||
|
ComponentDerivativeFactor(gtsam::Key key, const double z,
|
||||||
|
const gtsam::noiseModel::Base* model,
|
||||||
|
const size_t P, const size_t N, size_t i, double x,
|
||||||
|
double a, double b);
|
||||||
|
};
|
||||||
|
|
||||||
#include <gtsam/basis/FitBasis.h>
|
#include <gtsam/basis/FitBasis.h>
|
||||||
template <BASIS = {gtsam::FourierBasis, gtsam::Chebyshev1Basis,
|
template <BASIS = {gtsam::FourierBasis, gtsam::Chebyshev1Basis,
|
||||||
|
|
|
||||||
Loading…
Reference in New Issue