Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Windows Tests #1109

Merged
merged 18 commits into from
Feb 22, 2022
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Next Next commit
basis module tests pass
  • Loading branch information
varunagrawal committed Feb 17, 2022
commit 6e6c64749d9a319aa20840a03c0e4c0af1ca2c7b
7 changes: 1 addition & 6 deletions gtsam/basis/Basis.h
Original file line number Diff line number Diff line change
Expand Up @@ -92,7 +92,7 @@ Matrix kroneckerProductIdentity(const Weights& w) {

/// CRTP Base class for function bases
template <typename DERIVED>
class GTSAM_EXPORT Basis {
class Basis {
public:
/**
* Calculate weights for all x in vector X.
Expand Down Expand Up @@ -497,11 +497,6 @@ class GTSAM_EXPORT Basis {
}
};

// Vector version for MATLAB :-(
static double Derivative(double x, const Vector& p, //
OptionalJacobian</*1xN*/ -1, -1> H = boost::none) {
return DerivativeFunctor(x)(p.transpose(), H);
}
};

} // namespace gtsam
14 changes: 7 additions & 7 deletions gtsam/basis/BasisFactors.h
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ namespace gtsam {
* @tparam BASIS The basis class to use e.g. Chebyshev2
*/
template <class BASIS>
class GTSAM_EXPORT EvaluationFactor : public FunctorizedFactor<double, Vector> {
class EvaluationFactor : public FunctorizedFactor<double, Vector> {
private:
using Base = FunctorizedFactor<double, Vector>;

Expand Down Expand Up @@ -85,7 +85,7 @@ class GTSAM_EXPORT EvaluationFactor : public FunctorizedFactor<double, Vector> {
* @param M: Size of the evaluated state vector.
*/
template <class BASIS, int M>
class GTSAM_EXPORT VectorEvaluationFactor
class VectorEvaluationFactor
: public FunctorizedFactor<Vector, ParameterMatrix<M>> {
private:
using Base = FunctorizedFactor<Vector, ParameterMatrix<M>>;
Expand Down Expand Up @@ -148,7 +148,7 @@ class GTSAM_EXPORT VectorEvaluationFactor
* where N is the degree and i is the component index.
*/
template <class BASIS, size_t P>
class GTSAM_EXPORT VectorComponentFactor
class VectorComponentFactor
: public FunctorizedFactor<double, ParameterMatrix<P>> {
private:
using Base = FunctorizedFactor<double, ParameterMatrix<P>>;
Expand Down Expand Up @@ -217,7 +217,7 @@ class GTSAM_EXPORT VectorComponentFactor
* where `x` is the value (e.g. timestep) at which the rotation was evaluated.
*/
template <class BASIS, typename T>
class GTSAM_EXPORT ManifoldEvaluationFactor
class ManifoldEvaluationFactor
: public FunctorizedFactor<T, ParameterMatrix<traits<T>::dimension>> {
private:
using Base = FunctorizedFactor<T, ParameterMatrix<traits<T>::dimension>>;
Expand Down Expand Up @@ -269,7 +269,7 @@ class GTSAM_EXPORT ManifoldEvaluationFactor
* @param BASIS: The basis class to use e.g. Chebyshev2
*/
template <class BASIS>
class GTSAM_EXPORT DerivativeFactor
class DerivativeFactor
: public FunctorizedFactor<double, typename BASIS::Parameters> {
private:
using Base = FunctorizedFactor<double, typename BASIS::Parameters>;
Expand Down Expand Up @@ -318,7 +318,7 @@ class GTSAM_EXPORT DerivativeFactor
* @param M: Size of the evaluated state vector derivative.
*/
template <class BASIS, int M>
class GTSAM_EXPORT VectorDerivativeFactor
class VectorDerivativeFactor
: public FunctorizedFactor<Vector, ParameterMatrix<M>> {
private:
using Base = FunctorizedFactor<Vector, ParameterMatrix<M>>;
Expand Down Expand Up @@ -371,7 +371,7 @@ class GTSAM_EXPORT VectorDerivativeFactor
* @param P: Size of the control component derivative.
*/
template <class BASIS, int P>
class GTSAM_EXPORT ComponentDerivativeFactor
class ComponentDerivativeFactor
: public FunctorizedFactor<double, ParameterMatrix<P>> {
private:
using Base = FunctorizedFactor<double, ParameterMatrix<P>>;
Expand Down
4 changes: 2 additions & 2 deletions gtsam/basis/Chebyshev.h
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ namespace gtsam {
* These are typically denoted with the symbol T_n, where n is the degree.
* The parameter N is the number of coefficients, i.e., N = n+1.
*/
struct Chebyshev1Basis : Basis<Chebyshev1Basis> {
struct GTSAM_EXPORT Chebyshev1Basis : Basis<Chebyshev1Basis> {
using Parameters = Eigen::Matrix<double, -1, 1 /*Nx1*/>;

Parameters parameters_;
Expand Down Expand Up @@ -79,7 +79,7 @@ struct Chebyshev1Basis : Basis<Chebyshev1Basis> {
* functions. In this sense, they are like the sines and cosines of the Fourier
* basis.
*/
struct Chebyshev2Basis : Basis<Chebyshev2Basis> {
struct GTSAM_EXPORT Chebyshev2Basis : Basis<Chebyshev2Basis> {
using Parameters = Eigen::Matrix<double, -1, 1 /*Nx1*/>;

/**
Expand Down
2 changes: 1 addition & 1 deletion gtsam/basis/Fourier.h
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@
namespace gtsam {

/// Fourier basis
class GTSAM_EXPORT FourierBasis : public Basis<FourierBasis> {
class FourierBasis : public Basis<FourierBasis> {
public:
using Parameters = Eigen::Matrix<double, /*Nx1*/ -1, 1>;
using DiffMatrix = Eigen::Matrix<double, /*NxN*/ -1, -1>;
Expand Down
3 changes: 0 additions & 3 deletions gtsam/basis/basis.i
Original file line number Diff line number Diff line change
Expand Up @@ -44,9 +44,6 @@ class Chebyshev2 {
static Matrix DerivativeWeights(size_t N, double x, double a, double b);
static Matrix IntegrationWeights(size_t N, double a, double b);
static Matrix DifferentiationMatrix(size_t N, double a, double b);

// TODO Needs OptionalJacobian
// static double Derivative(double x, Vector f);
};

#include <gtsam/basis/ParameterMatrix.h>
Expand Down