commit
						267a4ae7dd
					
				| 
						 | 
				
			
			@ -106,6 +106,21 @@ jobs:
 | 
			
		|||
          cmake --build build -j 4 --config ${{ matrix.build_type }} --target gtsam
 | 
			
		||||
          cmake --build build -j 4 --config ${{ matrix.build_type }} --target gtsam_unstable
 | 
			
		||||
          cmake --build build -j 4 --config ${{ matrix.build_type }} --target wrap
 | 
			
		||||
 | 
			
		||||
          # Run GTSAM tests
 | 
			
		||||
          cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.base
 | 
			
		||||
          cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.base_unstable
 | 
			
		||||
          cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.basis
 | 
			
		||||
          cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.discrete
 | 
			
		||||
          #cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.geometry
 | 
			
		||||
          cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.inference
 | 
			
		||||
          cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.linear
 | 
			
		||||
          cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.navigation
 | 
			
		||||
          #cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.nonlinear
 | 
			
		||||
          #cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.sam
 | 
			
		||||
          cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.sfm
 | 
			
		||||
          #cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.slam
 | 
			
		||||
          cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.symbolic
 | 
			
		||||
 | 
			
		||||
          # Run GTSAM_UNSTABLE tests
 | 
			
		||||
          #cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.base_unstable
 | 
			
		||||
          
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -15,7 +15,7 @@ For example:
 | 
			
		|||
```cpp
 | 
			
		||||
class GTSAM_EXPORT MyClass { ... };
 | 
			
		||||
 | 
			
		||||
GTSAM_EXPORT myFunction();
 | 
			
		||||
GTSAM_EXPORT return_type myFunction();
 | 
			
		||||
```
 | 
			
		||||
 | 
			
		||||
More details [here](Using-GTSAM-EXPORT.md).
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -8,6 +8,7 @@ To create a DLL in windows, the `GTSAM_EXPORT` keyword has been created and need
 | 
			
		|||
    * At least one of the functions inside that class is declared in a .cpp file and not just the .h file.
 | 
			
		||||
    * You can `GTSAM_EXPORT` any class it inherits from as well.  (Note that this implictly requires the class does not derive from a "header-only" class.  Note that Eigen is a "header-only" library, so if your class derives from Eigen, _do not_ use `GTSAM_EXPORT` in the class definition!) 
 | 
			
		||||
3.  If you have defined a class using `GTSAM_EXPORT`, do not use `GTSAM_EXPORT` in any of its individual function declarations.  (Note that you _can_ put `GTSAM_EXPORT` in the definition of individual functions within a class as long as you don't put `GTSAM_EXPORT` in the class definition.)
 | 
			
		||||
4. For template specializations, you need to add `GTSAM_EXPORT` to each individual specialization.
 | 
			
		||||
 | 
			
		||||
## When is GTSAM_EXPORT being used incorrectly
 | 
			
		||||
Unfortunately, using `GTSAM_EXPORT` incorrectly often does not cause a compiler or linker error in the library that is being compiled, but only when you try to use that DLL in a different library.  For example, an error in `gtsam/base` will often show up when compiling the `check_base_program` or the MATLAB wrapper, but not when compiling/linking gtsam itself.  The most common errors will say something like:
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -93,6 +93,10 @@ if(MSVC)
 | 
			
		|||
	/wd4267 # warning C4267: 'initializing': conversion from 'size_t' to 'int', possible loss of data
 | 
			
		||||
  )
 | 
			
		||||
 | 
			
		||||
  add_compile_options(/wd4005)
 | 
			
		||||
  add_compile_options(/wd4101)
 | 
			
		||||
  add_compile_options(/wd4834)
 | 
			
		||||
 | 
			
		||||
endif()
 | 
			
		||||
 | 
			
		||||
# Other (non-preprocessor macros) compiler flags:
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -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.
 | 
			
		||||
| 
						 | 
				
			
			@ -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
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -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>;
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			@ -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>>;
 | 
			
		||||
| 
						 | 
				
			
			@ -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>>;
 | 
			
		||||
| 
						 | 
				
			
			@ -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>>;
 | 
			
		||||
| 
						 | 
				
			
			@ -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>;
 | 
			
		||||
| 
						 | 
				
			
			@ -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>>;
 | 
			
		||||
| 
						 | 
				
			
			@ -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>>;
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -29,7 +29,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_;
 | 
			
		||||
| 
						 | 
				
			
			@ -77,7 +77,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*/>;
 | 
			
		||||
 | 
			
		||||
  /**
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -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>;
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -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>
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -0,0 +1,28 @@
 | 
			
		|||
/* ----------------------------------------------------------------------------
 | 
			
		||||
 | 
			
		||||
 * GTSAM Copyright 2010, Georgia Tech Research Corporation,
 | 
			
		||||
 * Atlanta, Georgia 30332-0415
 | 
			
		||||
 * All Rights Reserved
 | 
			
		||||
 * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
 | 
			
		||||
 | 
			
		||||
 * See LICENSE for the license information
 | 
			
		||||
 | 
			
		||||
 * -------------------------------------------------------------------------- */
 | 
			
		||||
 | 
			
		||||
/**
 | 
			
		||||
 *  @file AlgebraicDecisionTree.cpp
 | 
			
		||||
 *  @date Feb 20, 2022
 | 
			
		||||
 *  @author Mike Sheffler
 | 
			
		||||
 *  @author Duy-Nguyen Ta
 | 
			
		||||
 *  @author Frank Dellaert
 | 
			
		||||
 */
 | 
			
		||||
 | 
			
		||||
#include "AlgebraicDecisionTree.h"
 | 
			
		||||
 | 
			
		||||
#include <gtsam/base/types.h>
 | 
			
		||||
 | 
			
		||||
namespace gtsam {
 | 
			
		||||
 | 
			
		||||
  template class AlgebraicDecisionTree<Key>;
 | 
			
		||||
 | 
			
		||||
}  // namespace gtsam
 | 
			
		||||
| 
						 | 
				
			
			@ -127,7 +127,7 @@ namespace gtsam {
 | 
			
		|||
        return map.at(label);
 | 
			
		||||
      };
 | 
			
		||||
      std::function<double(const double&)> op = Ring::id;
 | 
			
		||||
      this->root_ = this->template convertFrom(other.root_, L_of_M, op);
 | 
			
		||||
      this->root_ = DecisionTree<L, double>::convertFrom(other.root_, L_of_M, op);
 | 
			
		||||
    }
 | 
			
		||||
 | 
			
		||||
    /** sum */
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -36,7 +36,7 @@ class DiscreteBayesNet;
 | 
			
		|||
 * Inherits from discrete conditional for convenience, but is not normalized.
 | 
			
		||||
 * Is used in the max-product algorithm.
 | 
			
		||||
 */
 | 
			
		||||
class DiscreteLookupTable : public DiscreteConditional {
 | 
			
		||||
class GTSAM_EXPORT DiscreteLookupTable : public DiscreteConditional {
 | 
			
		||||
 public:
 | 
			
		||||
  using This = DiscreteLookupTable;
 | 
			
		||||
  using shared_ptr = boost::shared_ptr<This>;
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -29,7 +29,7 @@ namespace gtsam {
 | 
			
		|||
  /**
 | 
			
		||||
   * A class for computing marginals of variables in a DiscreteFactorGraph
 | 
			
		||||
   */
 | 
			
		||||
class GTSAM_EXPORT DiscreteMarginals {
 | 
			
		||||
class DiscreteMarginals {
 | 
			
		||||
 | 
			
		||||
  protected:
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -37,7 +37,7 @@ namespace gtsam {
 | 
			
		|||
 * stores cardinality of a Discrete variable. It should be handled naturally in
 | 
			
		||||
 * the new class DiscreteValue, as the variable's type (domain)
 | 
			
		||||
 */
 | 
			
		||||
class DiscreteValues : public Assignment<Key> {
 | 
			
		||||
class GTSAM_EXPORT DiscreteValues : public Assignment<Key> {
 | 
			
		||||
 public:
 | 
			
		||||
  using Base = Assignment<Key>;  // base class
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -318,7 +318,7 @@ TEST(ADT, factor_graph) {
 | 
			
		|||
  dot(fg, "Marginalized-3E");
 | 
			
		||||
  fg = fg.combine(L, &add_);
 | 
			
		||||
  dot(fg, "Marginalized-2L");
 | 
			
		||||
  EXPECT(adds = 54);
 | 
			
		||||
  LONGS_EQUAL(49, adds);
 | 
			
		||||
  gttoc_(marg);
 | 
			
		||||
  tictoc_getNode(margNode, marg);
 | 
			
		||||
  elapsed = margNode->secs() + margNode->wall();
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -117,4 +117,4 @@ Line3 transformTo(const Pose3 &wTc, const Line3 &wL,
 | 
			
		|||
  return Line3(cRl, c_ab[0], c_ab[1]);
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
}
 | 
			
		||||
}  // namespace gtsam
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -21,12 +21,27 @@
 | 
			
		|||
 | 
			
		||||
namespace gtsam {
 | 
			
		||||
 | 
			
		||||
class Line3;
 | 
			
		||||
 | 
			
		||||
/**
 | 
			
		||||
 * Transform a line from world to camera frame
 | 
			
		||||
 * @param wTc - Pose3 of camera in world frame
 | 
			
		||||
 * @param wL - Line3 in world frame
 | 
			
		||||
 * @param Dpose - OptionalJacobian of transformed line with respect to p
 | 
			
		||||
 * @param Dline -  OptionalJacobian of transformed line with respect to l
 | 
			
		||||
 * @return Transformed line in camera frame
 | 
			
		||||
 */
 | 
			
		||||
GTSAM_EXPORT Line3 transformTo(const Pose3 &wTc, const Line3 &wL,
 | 
			
		||||
                  OptionalJacobian<4, 6> Dpose = boost::none,
 | 
			
		||||
                  OptionalJacobian<4, 4> Dline = boost::none);
 | 
			
		||||
 | 
			
		||||
 | 
			
		||||
/**
 | 
			
		||||
 * A 3D line (R,a,b) : (Rot3,Scalar,Scalar)
 | 
			
		||||
 * @addtogroup geometry
 | 
			
		||||
 * \nosubgrouping
 | 
			
		||||
 */
 | 
			
		||||
class Line3 {
 | 
			
		||||
class GTSAM_EXPORT Line3 {
 | 
			
		||||
 private:
 | 
			
		||||
  Rot3 R_;    // Rotation of line about x and y in world frame
 | 
			
		||||
  double a_, b_;  // Intersection of line with the world x-y plane rotated by R_
 | 
			
		||||
| 
						 | 
				
			
			@ -136,18 +151,6 @@ class Line3 {
 | 
			
		|||
                           OptionalJacobian<4, 4> Dline);
 | 
			
		||||
};
 | 
			
		||||
 | 
			
		||||
/**
 | 
			
		||||
 * Transform a line from world to camera frame
 | 
			
		||||
 * @param wTc - Pose3 of camera in world frame
 | 
			
		||||
 * @param wL - Line3 in world frame
 | 
			
		||||
 * @param Dpose - OptionalJacobian of transformed line with respect to p
 | 
			
		||||
 * @param Dline -  OptionalJacobian of transformed line with respect to l
 | 
			
		||||
 * @return Transformed line in camera frame
 | 
			
		||||
 */
 | 
			
		||||
Line3 transformTo(const Pose3 &wTc, const Line3 &wL,
 | 
			
		||||
                  OptionalJacobian<4, 6> Dpose = boost::none,
 | 
			
		||||
                  OptionalJacobian<4, 4> Dline = boost::none);
 | 
			
		||||
 | 
			
		||||
template<>
 | 
			
		||||
struct traits<Line3> : public internal::Manifold<Line3> {};
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -22,7 +22,7 @@
 | 
			
		|||
namespace gtsam {
 | 
			
		||||
 | 
			
		||||
template <>
 | 
			
		||||
GTSAM_EXPORT void SOn::Hat(const Vector &xi, Eigen::Ref<Matrix> X) {
 | 
			
		||||
void SOn::Hat(const Vector &xi, Eigen::Ref<Matrix> X) {
 | 
			
		||||
  size_t n = AmbientDim(xi.size());
 | 
			
		||||
  if (n < 2)
 | 
			
		||||
    throw std::invalid_argument("SO<N>::Hat: n<2 not supported");
 | 
			
		||||
| 
						 | 
				
			
			@ -48,7 +48,7 @@ GTSAM_EXPORT void SOn::Hat(const Vector &xi, Eigen::Ref<Matrix> X) {
 | 
			
		|||
  }
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
template <> GTSAM_EXPORT Matrix SOn::Hat(const Vector &xi) {
 | 
			
		||||
template <> Matrix SOn::Hat(const Vector &xi) {
 | 
			
		||||
  size_t n = AmbientDim(xi.size());
 | 
			
		||||
  Matrix X(n, n); // allocate space for n*n skew-symmetric matrix
 | 
			
		||||
  SOn::Hat(xi, X);
 | 
			
		||||
| 
						 | 
				
			
			@ -56,7 +56,6 @@ template <> GTSAM_EXPORT Matrix SOn::Hat(const Vector &xi) {
 | 
			
		|||
}
 | 
			
		||||
 | 
			
		||||
template <>
 | 
			
		||||
GTSAM_EXPORT
 | 
			
		||||
Vector SOn::Vee(const Matrix& X) {
 | 
			
		||||
  const size_t n = X.rows();
 | 
			
		||||
  if (n < 2) throw std::invalid_argument("SO<N>::Hat: n<2 not supported");
 | 
			
		||||
| 
						 | 
				
			
			@ -104,7 +103,9 @@ SOn LieGroup<SOn, Eigen::Dynamic>::between(const SOn& g, DynamicJacobian H1,
 | 
			
		|||
}
 | 
			
		||||
 | 
			
		||||
// Dynamic version of vec
 | 
			
		||||
template <> typename SOn::VectorN2 SOn::vec(DynamicJacobian H) const {
 | 
			
		||||
template <>
 | 
			
		||||
typename SOn::VectorN2 SOn::vec(DynamicJacobian H) const
 | 
			
		||||
{
 | 
			
		||||
  const size_t n = rows(), n2 = n * n;
 | 
			
		||||
 | 
			
		||||
  // Vectorize
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -358,17 +358,21 @@ Vector SOn::Vee(const Matrix& X);
 | 
			
		|||
using DynamicJacobian = OptionalJacobian<Eigen::Dynamic, Eigen::Dynamic>;
 | 
			
		||||
 | 
			
		||||
template <>
 | 
			
		||||
GTSAM_EXPORT
 | 
			
		||||
SOn LieGroup<SOn, Eigen::Dynamic>::compose(const SOn& g, DynamicJacobian H1,
 | 
			
		||||
                                           DynamicJacobian H2) const;
 | 
			
		||||
 | 
			
		||||
template <>
 | 
			
		||||
GTSAM_EXPORT
 | 
			
		||||
SOn LieGroup<SOn, Eigen::Dynamic>::between(const SOn& g, DynamicJacobian H1,
 | 
			
		||||
                                           DynamicJacobian H2) const;
 | 
			
		||||
 | 
			
		||||
/*
 | 
			
		||||
 * Specialize dynamic vec.
 | 
			
		||||
 */
 | 
			
		||||
template <> typename SOn::VectorN2 SOn::vec(DynamicJacobian H) const;
 | 
			
		||||
template <> 
 | 
			
		||||
GTSAM_EXPORT
 | 
			
		||||
typename SOn::VectorN2 SOn::vec(DynamicJacobian H) const;
 | 
			
		||||
 | 
			
		||||
/** Serialization function */
 | 
			
		||||
template<class Archive>
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -40,7 +40,7 @@
 | 
			
		|||
namespace gtsam {
 | 
			
		||||
 | 
			
		||||
/// Represents a 3D point on a unit sphere.
 | 
			
		||||
class Unit3 {
 | 
			
		||||
class GTSAM_EXPORT Unit3 {
 | 
			
		||||
 | 
			
		||||
private:
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			@ -97,7 +97,7 @@ public:
 | 
			
		|||
  }
 | 
			
		||||
 | 
			
		||||
  /// Named constructor from Point3 with optional Jacobian
 | 
			
		||||
  GTSAM_EXPORT static Unit3 FromPoint3(const Point3& point, //
 | 
			
		||||
  static Unit3 FromPoint3(const Point3& point, //
 | 
			
		||||
      OptionalJacobian<2, 3> H = boost::none);
 | 
			
		||||
 | 
			
		||||
  /**
 | 
			
		||||
| 
						 | 
				
			
			@ -106,7 +106,7 @@ public:
 | 
			
		|||
   *   std::mt19937 engine(42);
 | 
			
		||||
   *   Unit3 unit = Unit3::Random(engine);
 | 
			
		||||
   */
 | 
			
		||||
  GTSAM_EXPORT static Unit3 Random(std::mt19937 & rng);
 | 
			
		||||
  static Unit3 Random(std::mt19937 & rng);
 | 
			
		||||
 | 
			
		||||
  /// @}
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			@ -116,7 +116,7 @@ public:
 | 
			
		|||
  friend std::ostream& operator<<(std::ostream& os, const Unit3& pair);
 | 
			
		||||
 | 
			
		||||
  /// The print fuction
 | 
			
		||||
  GTSAM_EXPORT void print(const std::string& s = std::string()) const;
 | 
			
		||||
  void print(const std::string& s = std::string()) const;
 | 
			
		||||
 | 
			
		||||
  /// The equals function with tolerance
 | 
			
		||||
  bool equals(const Unit3& s, double tol = 1e-9) const {
 | 
			
		||||
| 
						 | 
				
			
			@ -133,16 +133,16 @@ public:
 | 
			
		|||
   * tangent to the sphere at the current direction.
 | 
			
		||||
   * Provides derivatives of the basis with the two basis vectors stacked up as a 6x1.
 | 
			
		||||
   */
 | 
			
		||||
  GTSAM_EXPORT const Matrix32& basis(OptionalJacobian<6, 2> H = boost::none) const;
 | 
			
		||||
  const Matrix32& basis(OptionalJacobian<6, 2> H = boost::none) const;
 | 
			
		||||
 | 
			
		||||
  /// Return skew-symmetric associated with 3D point on unit sphere
 | 
			
		||||
  GTSAM_EXPORT Matrix3 skew() const;
 | 
			
		||||
  Matrix3 skew() const;
 | 
			
		||||
 | 
			
		||||
  /// Return unit-norm Point3
 | 
			
		||||
  GTSAM_EXPORT Point3 point3(OptionalJacobian<3, 2> H = boost::none) const;
 | 
			
		||||
  Point3 point3(OptionalJacobian<3, 2> H = boost::none) const;
 | 
			
		||||
 | 
			
		||||
  /// Return unit-norm Vector
 | 
			
		||||
  GTSAM_EXPORT Vector3 unitVector(OptionalJacobian<3, 2> H = boost::none) const;
 | 
			
		||||
  Vector3 unitVector(OptionalJacobian<3, 2> H = boost::none) const;
 | 
			
		||||
 | 
			
		||||
  /// Return scaled direction as Point3
 | 
			
		||||
  friend Point3 operator*(double s, const Unit3& d) {
 | 
			
		||||
| 
						 | 
				
			
			@ -150,20 +150,20 @@ public:
 | 
			
		|||
  }
 | 
			
		||||
 | 
			
		||||
  /// Return dot product with q
 | 
			
		||||
  GTSAM_EXPORT double dot(const Unit3& q, OptionalJacobian<1,2> H1 = boost::none, //
 | 
			
		||||
  double dot(const Unit3& q, OptionalJacobian<1,2> H1 = boost::none, //
 | 
			
		||||
                             OptionalJacobian<1,2> H2 = boost::none) const;
 | 
			
		||||
 | 
			
		||||
  /// Signed, vector-valued error between two directions
 | 
			
		||||
  /// @deprecated, errorVector has the proper derivatives, this confusingly has only the second.
 | 
			
		||||
  GTSAM_EXPORT Vector2 error(const Unit3& q, OptionalJacobian<2, 2> H_q = boost::none) const;
 | 
			
		||||
  Vector2 error(const Unit3& q, OptionalJacobian<2, 2> H_q = boost::none) const;
 | 
			
		||||
 | 
			
		||||
  /// Signed, vector-valued error between two directions
 | 
			
		||||
  /// NOTE(hayk): This method has zero derivatives if this (p) and q are orthogonal.
 | 
			
		||||
  GTSAM_EXPORT Vector2 errorVector(const Unit3& q, OptionalJacobian<2, 2> H_p = boost::none, //
 | 
			
		||||
  Vector2 errorVector(const Unit3& q, OptionalJacobian<2, 2> H_p = boost::none, //
 | 
			
		||||
                      OptionalJacobian<2, 2> H_q = boost::none) const;
 | 
			
		||||
 | 
			
		||||
  /// Distance between two directions
 | 
			
		||||
  GTSAM_EXPORT double distance(const Unit3& q, OptionalJacobian<1, 2> H = boost::none) const;
 | 
			
		||||
  double distance(const Unit3& q, OptionalJacobian<1, 2> H = boost::none) const;
 | 
			
		||||
 | 
			
		||||
  /// Cross-product between two Unit3s
 | 
			
		||||
  Unit3 cross(const Unit3& q) const {
 | 
			
		||||
| 
						 | 
				
			
			@ -196,10 +196,10 @@ public:
 | 
			
		|||
  };
 | 
			
		||||
 | 
			
		||||
  /// The retract function
 | 
			
		||||
  GTSAM_EXPORT Unit3 retract(const Vector2& v, OptionalJacobian<2,2> H = boost::none) const;
 | 
			
		||||
  Unit3 retract(const Vector2& v, OptionalJacobian<2,2> H = boost::none) const;
 | 
			
		||||
 | 
			
		||||
  /// The local coordinates function
 | 
			
		||||
  GTSAM_EXPORT Vector2 localCoordinates(const Unit3& s) const;
 | 
			
		||||
  Vector2 localCoordinates(const Unit3& s) const;
 | 
			
		||||
 | 
			
		||||
  /// @}
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -270,17 +270,7 @@ TEST(Ordering, MetisLoop) {
 | 
			
		|||
  symbolicGraph.push_factor(0, 5);
 | 
			
		||||
 | 
			
		||||
  // METIS
 | 
			
		||||
#if !defined(__APPLE__)
 | 
			
		||||
  {
 | 
			
		||||
    Ordering actual = Ordering::Create(Ordering::METIS, symbolicGraph);
 | 
			
		||||
    //  - P( 0 4 1)
 | 
			
		||||
    //  | - P( 2 | 4 1)
 | 
			
		||||
    //  | | - P( 3 | 4 2)
 | 
			
		||||
    //  | - P( 5 | 0 1)
 | 
			
		||||
    Ordering expected = Ordering(list_of(3)(2)(5)(0)(4)(1));
 | 
			
		||||
    EXPECT(assert_equal(expected, actual));
 | 
			
		||||
  }
 | 
			
		||||
#else
 | 
			
		||||
#if defined(__APPLE__)
 | 
			
		||||
  {
 | 
			
		||||
    Ordering actual = Ordering::Create(Ordering::METIS, symbolicGraph);
 | 
			
		||||
    //  - P( 1 0 3)
 | 
			
		||||
| 
						 | 
				
			
			@ -290,6 +280,26 @@ TEST(Ordering, MetisLoop) {
 | 
			
		|||
    Ordering expected = Ordering(list_of(5)(4)(2)(1)(0)(3));
 | 
			
		||||
    EXPECT(assert_equal(expected, actual));
 | 
			
		||||
  }
 | 
			
		||||
#elif defined(_WIN32)
 | 
			
		||||
  {
 | 
			
		||||
    Ordering actual = Ordering::Create(Ordering::METIS, symbolicGraph);
 | 
			
		||||
    //  - P( 0 5 2)
 | 
			
		||||
    //  | - P( 3 | 5 2)
 | 
			
		||||
    //  | | - P( 4 | 5 3)
 | 
			
		||||
    //  | - P( 1 | 0 2)
 | 
			
		||||
    Ordering expected = Ordering(list_of(4)(3)(1)(0)(5)(2));
 | 
			
		||||
    EXPECT(assert_equal(expected, actual));
 | 
			
		||||
  }
 | 
			
		||||
#else
 | 
			
		||||
  {
 | 
			
		||||
    Ordering actual = Ordering::Create(Ordering::METIS, symbolicGraph);
 | 
			
		||||
    //  - P( 0 4 1)
 | 
			
		||||
    //  | - P( 2 | 4 1)
 | 
			
		||||
    //  | | - P( 3 | 4 2)
 | 
			
		||||
    //  | - P( 5 | 0 1)
 | 
			
		||||
    Ordering expected = Ordering(list_of(3)(2)(5)(0)(4)(1));
 | 
			
		||||
    EXPECT(assert_equal(expected, actual));
 | 
			
		||||
  }
 | 
			
		||||
#endif
 | 
			
		||||
}
 | 
			
		||||
#endif
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -256,6 +256,3 @@ std::ostream& operator<<(std::ostream& os, const CombinedImuFactor& f) {
 | 
			
		|||
}
 | 
			
		||||
 /// namespace gtsam
 | 
			
		||||
 | 
			
		||||
/// Boost serialization export definition for derived class
 | 
			
		||||
BOOST_CLASS_EXPORT_IMPLEMENT(gtsam::PreintegrationCombinedParams)
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -351,6 +351,3 @@ template <>
 | 
			
		|||
struct traits<CombinedImuFactor> : public Testable<CombinedImuFactor> {};
 | 
			
		||||
 | 
			
		||||
}  // namespace gtsam
 | 
			
		||||
 | 
			
		||||
/// Add Boost serialization export key (declaration) for derived class
 | 
			
		||||
BOOST_CLASS_EXPORT_KEY(gtsam::PreintegrationCombinedParams)
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -39,6 +39,9 @@ BOOST_CLASS_EXPORT_GUID(noiseModel::Unit, "gtsam_noiseModel_Unit")
 | 
			
		|||
BOOST_CLASS_EXPORT_GUID(noiseModel::Isotropic, "gtsam_noiseModel_Isotropic")
 | 
			
		||||
BOOST_CLASS_EXPORT_GUID(SharedNoiseModel, "gtsam_SharedNoiseModel")
 | 
			
		||||
BOOST_CLASS_EXPORT_GUID(SharedDiagonal, "gtsam_SharedDiagonal")
 | 
			
		||||
BOOST_CLASS_EXPORT_GUID(PreintegratedImuMeasurements, "gtsam_PreintegratedImuMeasurements")
 | 
			
		||||
BOOST_CLASS_EXPORT_GUID(PreintegrationCombinedParams, "gtsam_PreintegrationCombinedParams")
 | 
			
		||||
BOOST_CLASS_EXPORT_GUID(PreintegratedCombinedMeasurements, "gtsam_PreintegratedCombinedMeasurements")
 | 
			
		||||
 | 
			
		||||
template <typename P>
 | 
			
		||||
P getPreintegratedMeasurements() {
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -56,7 +56,7 @@ namespace gtsam {
 | 
			
		|||
 *     MultiplyFunctor(multiplier));
 | 
			
		||||
 */
 | 
			
		||||
template <typename R, typename T>
 | 
			
		||||
class GTSAM_EXPORT FunctorizedFactor : public NoiseModelFactor1<T> {
 | 
			
		||||
class FunctorizedFactor : public NoiseModelFactor1<T> {
 | 
			
		||||
 private:
 | 
			
		||||
  using Base = NoiseModelFactor1<T>;
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			@ -155,7 +155,7 @@ FunctorizedFactor<R, T> MakeFunctorizedFactor(Key key, const R &z,
 | 
			
		|||
 * @param T2: The second argument type for the functor.
 | 
			
		||||
 */
 | 
			
		||||
template <typename R, typename T1, typename T2>
 | 
			
		||||
class GTSAM_EXPORT FunctorizedFactor2 : public NoiseModelFactor2<T1, T2> {
 | 
			
		||||
class FunctorizedFactor2 : public NoiseModelFactor2<T1, T2> {
 | 
			
		||||
 private:
 | 
			
		||||
  using Base = NoiseModelFactor2<T1, T2>;
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -23,14 +23,14 @@ namespace gtsam {
 | 
			
		|||
 * This factor does have the ability to perform relinearization under small-angle and
 | 
			
		||||
 * linearity assumptions if a linearization point is added.
 | 
			
		||||
 */
 | 
			
		||||
class LinearContainerFactor : public NonlinearFactor {
 | 
			
		||||
class GTSAM_EXPORT LinearContainerFactor : public NonlinearFactor {
 | 
			
		||||
protected:
 | 
			
		||||
 | 
			
		||||
  GaussianFactor::shared_ptr factor_;
 | 
			
		||||
  boost::optional<Values> linearizationPoint_;
 | 
			
		||||
 | 
			
		||||
  /** direct copy constructor */
 | 
			
		||||
  GTSAM_EXPORT LinearContainerFactor(const GaussianFactor::shared_ptr& factor, const boost::optional<Values>& linearizationPoint);
 | 
			
		||||
  LinearContainerFactor(const GaussianFactor::shared_ptr& factor, const boost::optional<Values>& linearizationPoint);
 | 
			
		||||
 | 
			
		||||
  // Some handy typedefs
 | 
			
		||||
  typedef NonlinearFactor Base;
 | 
			
		||||
| 
						 | 
				
			
			@ -44,13 +44,13 @@ public:
 | 
			
		|||
  LinearContainerFactor() {}
 | 
			
		||||
 | 
			
		||||
  /** Primary constructor: store a linear factor with optional linearization point */
 | 
			
		||||
  GTSAM_EXPORT LinearContainerFactor(const JacobianFactor& factor, const Values& linearizationPoint = Values());
 | 
			
		||||
  LinearContainerFactor(const JacobianFactor& factor, const Values& linearizationPoint = Values());
 | 
			
		||||
 | 
			
		||||
  /** Primary constructor: store a linear factor with optional linearization point */
 | 
			
		||||
  GTSAM_EXPORT LinearContainerFactor(const HessianFactor& factor, const Values& linearizationPoint = Values());
 | 
			
		||||
  LinearContainerFactor(const HessianFactor& factor, const Values& linearizationPoint = Values());
 | 
			
		||||
 | 
			
		||||
  /** Constructor from shared_ptr */
 | 
			
		||||
  GTSAM_EXPORT LinearContainerFactor(const GaussianFactor::shared_ptr& factor, const Values& linearizationPoint = Values());
 | 
			
		||||
  LinearContainerFactor(const GaussianFactor::shared_ptr& factor, const Values& linearizationPoint = Values());
 | 
			
		||||
 | 
			
		||||
  // Access
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			@ -59,10 +59,10 @@ public:
 | 
			
		|||
  // Testable
 | 
			
		||||
 | 
			
		||||
  /** print */
 | 
			
		||||
  GTSAM_EXPORT void print(const std::string& s = "", const KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter) const override;
 | 
			
		||||
  void print(const std::string& s = "", const KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter) const override;
 | 
			
		||||
 | 
			
		||||
  /** Check if two factors are equal */
 | 
			
		||||
  GTSAM_EXPORT bool equals(const NonlinearFactor& f, double tol = 1e-9) const override;
 | 
			
		||||
  bool equals(const NonlinearFactor& f, double tol = 1e-9) const override;
 | 
			
		||||
 | 
			
		||||
  // NonlinearFactor
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			@ -74,10 +74,10 @@ public:
 | 
			
		|||
   *
 | 
			
		||||
   * @return nonlinear error if linearizationPoint present, zero otherwise
 | 
			
		||||
   */
 | 
			
		||||
  GTSAM_EXPORT double error(const Values& c) const override;
 | 
			
		||||
  double error(const Values& c) const override;
 | 
			
		||||
 | 
			
		||||
  /** get the dimension of the factor: rows of linear factor */
 | 
			
		||||
  GTSAM_EXPORT size_t dim() const override;
 | 
			
		||||
  size_t dim() const override;
 | 
			
		||||
 | 
			
		||||
  /** Extract the linearization point used in recalculating error */
 | 
			
		||||
  const boost::optional<Values>& linearizationPoint() const { return linearizationPoint_; }
 | 
			
		||||
| 
						 | 
				
			
			@ -98,17 +98,17 @@ public:
 | 
			
		|||
   * TODO: better approximation of relinearization
 | 
			
		||||
   * TODO: switchable modes for approximation technique
 | 
			
		||||
   */
 | 
			
		||||
  GTSAM_EXPORT GaussianFactor::shared_ptr linearize(const Values& c) const override;
 | 
			
		||||
  GaussianFactor::shared_ptr linearize(const Values& c) const override;
 | 
			
		||||
 | 
			
		||||
  /**
 | 
			
		||||
   * Creates an anti-factor directly
 | 
			
		||||
   */
 | 
			
		||||
  GTSAM_EXPORT GaussianFactor::shared_ptr negateToGaussian() const;
 | 
			
		||||
  GaussianFactor::shared_ptr negateToGaussian() const;
 | 
			
		||||
 | 
			
		||||
  /**
 | 
			
		||||
   * Creates the equivalent anti-factor as another LinearContainerFactor.
 | 
			
		||||
   */
 | 
			
		||||
  GTSAM_EXPORT NonlinearFactor::shared_ptr negateToNonlinear() const;
 | 
			
		||||
  NonlinearFactor::shared_ptr negateToNonlinear() const;
 | 
			
		||||
 | 
			
		||||
  /**
 | 
			
		||||
   * Creates a shared_ptr clone of the factor - needs to be specialized to allow
 | 
			
		||||
| 
						 | 
				
			
			@ -140,25 +140,24 @@ public:
 | 
			
		|||
  /**
 | 
			
		||||
   * Simple checks whether this is a Jacobian or Hessian factor
 | 
			
		||||
   */
 | 
			
		||||
  GTSAM_EXPORT bool isJacobian() const;
 | 
			
		||||
  GTSAM_EXPORT bool isHessian() const;
 | 
			
		||||
  bool isJacobian() const;
 | 
			
		||||
  bool isHessian() const;
 | 
			
		||||
 | 
			
		||||
  /** Casts to JacobianFactor */
 | 
			
		||||
  GTSAM_EXPORT boost::shared_ptr<JacobianFactor> toJacobian() const;
 | 
			
		||||
  boost::shared_ptr<JacobianFactor> toJacobian() const;
 | 
			
		||||
 | 
			
		||||
  /** Casts to HessianFactor */
 | 
			
		||||
  GTSAM_EXPORT boost::shared_ptr<HessianFactor> toHessian() const;
 | 
			
		||||
  boost::shared_ptr<HessianFactor> toHessian() const;
 | 
			
		||||
 | 
			
		||||
  /**
 | 
			
		||||
   * Utility function for converting linear graphs to nonlinear graphs
 | 
			
		||||
   * consisting of LinearContainerFactors.
 | 
			
		||||
   */
 | 
			
		||||
  GTSAM_EXPORT
 | 
			
		||||
  static NonlinearFactorGraph ConvertLinearGraph(const GaussianFactorGraph& linear_graph,
 | 
			
		||||
      const Values& linearizationPoint = Values());
 | 
			
		||||
 | 
			
		||||
 protected:
 | 
			
		||||
  GTSAM_EXPORT void initializeLinearizationPoint(const Values& linearizationPoint);
 | 
			
		||||
  void initializeLinearizationPoint(const Values& linearizationPoint);
 | 
			
		||||
 | 
			
		||||
 private:
 | 
			
		||||
  /** Serialization function */
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -48,7 +48,7 @@ ConvertNoiseModel(const SharedNoiseModel &model, size_t n,
 | 
			
		|||
 * element of SO(3) or SO(4).
 | 
			
		||||
 */
 | 
			
		||||
template <class Rot>
 | 
			
		||||
class GTSAM_EXPORT FrobeniusPrior : public NoiseModelFactor1<Rot> {
 | 
			
		||||
class FrobeniusPrior : public NoiseModelFactor1<Rot> {
 | 
			
		||||
  enum { Dim = Rot::VectorN2::RowsAtCompileTime };
 | 
			
		||||
  using MatrixNN = typename Rot::MatrixNN;
 | 
			
		||||
  Eigen::Matrix<double, Dim, 1> vecM_;  ///< vectorized matrix to approximate
 | 
			
		||||
| 
						 | 
				
			
			@ -75,7 +75,7 @@ class GTSAM_EXPORT FrobeniusPrior : public NoiseModelFactor1<Rot> {
 | 
			
		|||
 * The template argument can be any fixed-size SO<N>.
 | 
			
		||||
 */
 | 
			
		||||
template <class Rot>
 | 
			
		||||
class GTSAM_EXPORT FrobeniusFactor : public NoiseModelFactor2<Rot, Rot> {
 | 
			
		||||
class FrobeniusFactor : public NoiseModelFactor2<Rot, Rot> {
 | 
			
		||||
  enum { Dim = Rot::VectorN2::RowsAtCompileTime };
 | 
			
		||||
 | 
			
		||||
 public:
 | 
			
		||||
| 
						 | 
				
			
			@ -101,7 +101,7 @@ class GTSAM_EXPORT FrobeniusFactor : public NoiseModelFactor2<Rot, Rot> {
 | 
			
		|||
 * and in fact only SO3 and SO4 really work, as we need SO<N>::AdjointMap.
 | 
			
		||||
 */
 | 
			
		||||
template <class Rot>
 | 
			
		||||
class GTSAM_EXPORT FrobeniusBetweenFactor : public NoiseModelFactor2<Rot, Rot> {
 | 
			
		||||
class FrobeniusBetweenFactor : public NoiseModelFactor2<Rot, Rot> {
 | 
			
		||||
  Rot R12_;  ///< measured rotation between R1 and R2
 | 
			
		||||
  Eigen::Matrix<double, Rot::dimension, Rot::dimension>
 | 
			
		||||
      R2hat_H_R1_;  ///< fixed derivative of R2hat wrpt R1
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -15,7 +15,7 @@ namespace gtsam {
 | 
			
		|||
/**
 | 
			
		||||
 * Factor to measure a planar landmark from a given pose
 | 
			
		||||
 */
 | 
			
		||||
class OrientedPlane3Factor: public NoiseModelFactor2<Pose3, OrientedPlane3> {
 | 
			
		||||
class GTSAM_EXPORT OrientedPlane3Factor: public NoiseModelFactor2<Pose3, OrientedPlane3> {
 | 
			
		||||
 protected:
 | 
			
		||||
  OrientedPlane3 measured_p_;
 | 
			
		||||
  typedef NoiseModelFactor2<Pose3, OrientedPlane3> Base;
 | 
			
		||||
| 
						 | 
				
			
			@ -49,7 +49,7 @@ class OrientedPlane3Factor: public NoiseModelFactor2<Pose3, OrientedPlane3> {
 | 
			
		|||
};
 | 
			
		||||
 | 
			
		||||
// TODO: Convert this factor to dimension two, three dimensions is redundant for direction prior
 | 
			
		||||
class OrientedPlane3DirectionPrior : public NoiseModelFactor1<OrientedPlane3> {
 | 
			
		||||
class GTSAM_EXPORT OrientedPlane3DirectionPrior : public NoiseModelFactor1<OrientedPlane3> {
 | 
			
		||||
 protected:
 | 
			
		||||
  OrientedPlane3 measured_p_;  /// measured plane parameters
 | 
			
		||||
  typedef NoiseModelFactor1<OrientedPlane3> Base;
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -42,7 +42,7 @@ namespace gtsam {
 | 
			
		|||
 * @addtogroup SLAM
 | 
			
		||||
 */
 | 
			
		||||
template <class CALIBRATION>
 | 
			
		||||
class GTSAM_EXPORT SmartProjectionPoseFactor
 | 
			
		||||
class SmartProjectionPoseFactor
 | 
			
		||||
    : public SmartProjectionFactor<PinholePose<CALIBRATION> > {
 | 
			
		||||
 private:
 | 
			
		||||
  typedef PinholePose<CALIBRATION> Camera;
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -177,8 +177,8 @@ boost::optional<IndexedPose> parseVertexPose(istream &is, const string &tag) {
 | 
			
		|||
}
 | 
			
		||||
 | 
			
		||||
template <>
 | 
			
		||||
std::map<size_t, Pose2> parseVariables<Pose2>(const std::string &filename,
 | 
			
		||||
                                              size_t maxIndex) {
 | 
			
		||||
GTSAM_EXPORT std::map<size_t, Pose2> parseVariables<Pose2>(
 | 
			
		||||
    const std::string &filename, size_t maxIndex) {
 | 
			
		||||
  return parseToMap<Pose2>(filename, parseVertexPose, maxIndex);
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			@ -199,8 +199,8 @@ boost::optional<IndexedLandmark> parseVertexLandmark(istream &is,
 | 
			
		|||
}
 | 
			
		||||
 | 
			
		||||
template <>
 | 
			
		||||
std::map<size_t, Point2> parseVariables<Point2>(const std::string &filename,
 | 
			
		||||
                                                size_t maxIndex) {
 | 
			
		||||
GTSAM_EXPORT std::map<size_t, Point2> parseVariables<Point2>(
 | 
			
		||||
    const std::string &filename, size_t maxIndex) {
 | 
			
		||||
  return parseToMap<Point2>(filename, parseVertexLandmark, maxIndex);
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			@ -384,6 +384,7 @@ boost::shared_ptr<Sampler> createSampler(const SharedNoiseModel &model) {
 | 
			
		|||
/* ************************************************************************* */
 | 
			
		||||
// Implementation of parseMeasurements for Pose2
 | 
			
		||||
template <>
 | 
			
		||||
GTSAM_EXPORT
 | 
			
		||||
std::vector<BinaryMeasurement<Pose2>>
 | 
			
		||||
parseMeasurements(const std::string &filename,
 | 
			
		||||
                  const noiseModel::Diagonal::shared_ptr &model,
 | 
			
		||||
| 
						 | 
				
			
			@ -411,6 +412,7 @@ static BinaryMeasurement<Rot2> convert(const BinaryMeasurement<Pose2> &p) {
 | 
			
		|||
}
 | 
			
		||||
 | 
			
		||||
template <>
 | 
			
		||||
GTSAM_EXPORT
 | 
			
		||||
std::vector<BinaryMeasurement<Rot2>>
 | 
			
		||||
parseMeasurements(const std::string &filename,
 | 
			
		||||
                  const noiseModel::Diagonal::shared_ptr &model,
 | 
			
		||||
| 
						 | 
				
			
			@ -426,6 +428,7 @@ parseMeasurements(const std::string &filename,
 | 
			
		|||
/* ************************************************************************* */
 | 
			
		||||
// Implementation of parseFactors for Pose2
 | 
			
		||||
template <>
 | 
			
		||||
GTSAM_EXPORT
 | 
			
		||||
std::vector<BetweenFactor<Pose2>::shared_ptr>
 | 
			
		||||
parseFactors<Pose2>(const std::string &filename,
 | 
			
		||||
                    const noiseModel::Diagonal::shared_ptr &model,
 | 
			
		||||
| 
						 | 
				
			
			@ -775,8 +778,8 @@ boost::optional<pair<size_t, Pose3>> parseVertexPose3(istream &is,
 | 
			
		|||
}
 | 
			
		||||
 | 
			
		||||
template <>
 | 
			
		||||
std::map<size_t, Pose3> parseVariables<Pose3>(const std::string &filename,
 | 
			
		||||
                                              size_t maxIndex) {
 | 
			
		||||
GTSAM_EXPORT std::map<size_t, Pose3> parseVariables<Pose3>(
 | 
			
		||||
    const std::string &filename, size_t maxIndex) {
 | 
			
		||||
  return parseToMap<Pose3>(filename, parseVertexPose3, maxIndex);
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			@ -793,8 +796,8 @@ boost::optional<pair<size_t, Point3>> parseVertexPoint3(istream &is,
 | 
			
		|||
}
 | 
			
		||||
 | 
			
		||||
template <>
 | 
			
		||||
std::map<size_t, Point3> parseVariables<Point3>(const std::string &filename,
 | 
			
		||||
                                                size_t maxIndex) {
 | 
			
		||||
GTSAM_EXPORT std::map<size_t, Point3> parseVariables<Point3>(
 | 
			
		||||
    const std::string &filename, size_t maxIndex) {
 | 
			
		||||
  return parseToMap<Point3>(filename, parseVertexPoint3, maxIndex);
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			@ -868,6 +871,7 @@ template <> struct ParseMeasurement<Pose3> {
 | 
			
		|||
/* ************************************************************************* */
 | 
			
		||||
// Implementation of parseMeasurements for Pose3
 | 
			
		||||
template <>
 | 
			
		||||
GTSAM_EXPORT
 | 
			
		||||
std::vector<BinaryMeasurement<Pose3>>
 | 
			
		||||
parseMeasurements(const std::string &filename,
 | 
			
		||||
                  const noiseModel::Diagonal::shared_ptr &model,
 | 
			
		||||
| 
						 | 
				
			
			@ -895,6 +899,7 @@ static BinaryMeasurement<Rot3> convert(const BinaryMeasurement<Pose3> &p) {
 | 
			
		|||
}
 | 
			
		||||
 | 
			
		||||
template <>
 | 
			
		||||
GTSAM_EXPORT
 | 
			
		||||
std::vector<BinaryMeasurement<Rot3>>
 | 
			
		||||
parseMeasurements(const std::string &filename,
 | 
			
		||||
                  const noiseModel::Diagonal::shared_ptr &model,
 | 
			
		||||
| 
						 | 
				
			
			@ -910,6 +915,7 @@ parseMeasurements(const std::string &filename,
 | 
			
		|||
/* ************************************************************************* */
 | 
			
		||||
// Implementation of parseFactors for Pose3
 | 
			
		||||
template <>
 | 
			
		||||
GTSAM_EXPORT
 | 
			
		||||
std::vector<BetweenFactor<Pose3>::shared_ptr>
 | 
			
		||||
parseFactors<Pose3>(const std::string &filename,
 | 
			
		||||
                    const noiseModel::Diagonal::shared_ptr &model,
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -731,10 +731,12 @@ TEST(SymbolicBayesTree, COLAMDvsMETIS) {
 | 
			
		|||
  {
 | 
			
		||||
    Ordering ordering = Ordering::Create(Ordering::METIS, sfg);
 | 
			
		||||
// Linux and Mac split differently when using mettis
 | 
			
		||||
#if !defined(__APPLE__)
 | 
			
		||||
    EXPECT(assert_equal(Ordering(list_of(3)(2)(5)(0)(4)(1)), ordering));
 | 
			
		||||
#else
 | 
			
		||||
#if defined(__APPLE__)
 | 
			
		||||
    EXPECT(assert_equal(Ordering(list_of(5)(4)(2)(1)(0)(3)), ordering));
 | 
			
		||||
#elif defined(_WIN32)
 | 
			
		||||
    EXPECT(assert_equal(Ordering(list_of(4)(3)(1)(0)(5)(2)), ordering));
 | 
			
		||||
#else
 | 
			
		||||
    EXPECT(assert_equal(Ordering(list_of(3)(2)(5)(0)(4)(1)), ordering));
 | 
			
		||||
#endif
 | 
			
		||||
 | 
			
		||||
    //  - P( 1 0 3)
 | 
			
		||||
| 
						 | 
				
			
			@ -742,20 +744,27 @@ TEST(SymbolicBayesTree, COLAMDvsMETIS) {
 | 
			
		|||
    //  | | - P( 5 | 0 4)
 | 
			
		||||
    //  | - P( 2 | 1 3)
 | 
			
		||||
    SymbolicBayesTree expected;
 | 
			
		||||
#if !defined(__APPLE__)
 | 
			
		||||
    expected.insertRoot(
 | 
			
		||||
        MakeClique(list_of(2)(4)(1), 3,
 | 
			
		||||
            list_of(
 | 
			
		||||
                MakeClique(list_of(0)(1)(4), 1,
 | 
			
		||||
                    list_of(MakeClique(list_of(5)(0)(4), 1))))(
 | 
			
		||||
                MakeClique(list_of(3)(2)(4), 1))));
 | 
			
		||||
#else
 | 
			
		||||
#if defined(__APPLE__)
 | 
			
		||||
    expected.insertRoot(
 | 
			
		||||
            MakeClique(list_of(1)(0)(3), 3,
 | 
			
		||||
                list_of(
 | 
			
		||||
                    MakeClique(list_of(4)(0)(3), 1,
 | 
			
		||||
                        list_of(MakeClique(list_of(5)(0)(4), 1))))(
 | 
			
		||||
                    MakeClique(list_of(2)(1)(3), 1))));
 | 
			
		||||
#elif defined(_WIN32)
 | 
			
		||||
    expected.insertRoot(
 | 
			
		||||
            MakeClique(list_of(3)(5)(2), 3,
 | 
			
		||||
                list_of(
 | 
			
		||||
                    MakeClique(list_of(4)(3)(5), 1,
 | 
			
		||||
                        list_of(MakeClique(list_of(0)(2)(5), 1))))(
 | 
			
		||||
                    MakeClique(list_of(1)(0)(2), 1))));
 | 
			
		||||
#else
 | 
			
		||||
    expected.insertRoot(
 | 
			
		||||
        MakeClique(list_of(2)(4)(1), 3,
 | 
			
		||||
            list_of(
 | 
			
		||||
                MakeClique(list_of(0)(1)(4), 1,
 | 
			
		||||
                    list_of(MakeClique(list_of(5)(0)(4), 1))))(
 | 
			
		||||
                MakeClique(list_of(3)(2)(4), 1))));
 | 
			
		||||
#endif
 | 
			
		||||
    SymbolicBayesTree actual = *sfg.eliminateMultifrontal(ordering);
 | 
			
		||||
    EXPECT(assert_equal(expected, actual));
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
		Loading…
	
		Reference in New Issue