some more comments
parent
376c910e2b
commit
8506877a52
|
@ -140,6 +140,7 @@ class GTSAM_EXPORT AHRSFactor: public NoiseModelFactorN<Rot3, Rot3, Vector3> {
|
|||
|
||||
public:
|
||||
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
/** Shorthand for a smart pointer to a factor */
|
||||
#if !defined(_MSC_VER) && __GNUC__ == 4 && __GNUC_MINOR__ > 5
|
||||
|
|
|
@ -82,6 +82,7 @@ class GTSAM_EXPORT Rot3AttitudeFactor: public NoiseModelFactorN<Rot3>, public At
|
|||
|
||||
public:
|
||||
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
/// shorthand for a smart pointer to a factor
|
||||
typedef boost::shared_ptr<Rot3AttitudeFactor> shared_ptr;
|
||||
|
@ -156,6 +157,7 @@ class GTSAM_EXPORT Pose3AttitudeFactor: public NoiseModelFactorN<Pose3>,
|
|||
typedef NoiseModelFactorN<Pose3> Base;
|
||||
|
||||
public:
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
|
||||
/// shorthand for a smart pointer to a factor
|
||||
|
|
|
@ -38,6 +38,7 @@ class GTSAM_EXPORT BarometricFactor : public NoiseModelFactorN<Pose3, double> {
|
|||
double nT_; ///< Height Measurement based on a standard atmosphere
|
||||
|
||||
public:
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
/// shorthand for a smart pointer to a factor
|
||||
typedef boost::shared_ptr<BarometricFactor> shared_ptr;
|
||||
|
|
|
@ -42,6 +42,7 @@ private:
|
|||
|
||||
public:
|
||||
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
/// shorthand for a smart pointer to a factor
|
||||
typedef boost::shared_ptr<GPSFactor> shared_ptr;
|
||||
|
@ -120,6 +121,7 @@ private:
|
|||
Point3 nT_; ///< Position measurement in cartesian coordinates
|
||||
|
||||
public:
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
|
||||
/// shorthand for a smart pointer to a factor
|
||||
|
|
|
@ -179,6 +179,7 @@ private:
|
|||
PreintegratedImuMeasurements _PIM_;
|
||||
|
||||
public:
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
|
||||
/** Shorthand for a smart pointer to a factor */
|
||||
|
|
|
@ -49,6 +49,7 @@ class MagPoseFactor: public NoiseModelFactorN<POSE> {
|
|||
GTSAM_CONCEPT_POSE_TYPE(POSE)
|
||||
|
||||
public:
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
|
||||
~MagPoseFactor() override {}
|
||||
|
|
|
@ -65,6 +65,7 @@ class FunctorizedFactor : public NoiseModelFactorN<T> {
|
|||
std::function<R(T, OptionalMatrixType)> func_; ///< functor instance
|
||||
|
||||
public:
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
/** default constructor - only use for serialization */
|
||||
FunctorizedFactor() {}
|
||||
|
@ -166,6 +167,7 @@ class FunctorizedFactor2 : public NoiseModelFactorN<T1, T2> {
|
|||
FunctionType func_; ///< functor instance
|
||||
|
||||
public:
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
/** default constructor - only use for serialization */
|
||||
FunctorizedFactor2() {}
|
||||
|
|
|
@ -305,6 +305,7 @@ class NonlinearEquality2 : public NoiseModelFactorN<T, T> {
|
|||
|
||||
public:
|
||||
typedef boost::shared_ptr<NonlinearEquality2<T>> shared_ptr;
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
|
||||
/**
|
||||
|
|
|
@ -117,6 +117,7 @@ class EssentialMatrixFactor2
|
|||
typedef EssentialMatrixFactor2 This;
|
||||
|
||||
public:
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
/**
|
||||
* Constructor
|
||||
|
|
|
@ -74,6 +74,7 @@ class RotateDirectionsFactor: public NoiseModelFactorN<Rot3> {
|
|||
typedef RotateDirectionsFactor This;
|
||||
|
||||
public:
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
|
||||
/// Constructor
|
||||
|
|
|
@ -32,6 +32,7 @@ protected:
|
|||
double dt_; /// time between measurements
|
||||
|
||||
public:
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
|
||||
/** Standard constructor */
|
||||
|
|
|
@ -53,6 +53,7 @@ private:
|
|||
Vector tau_;
|
||||
|
||||
public:
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
|
||||
// shorthand for a smart pointer to a factor
|
||||
|
|
|
@ -133,6 +133,7 @@ namespace simulated2D {
|
|||
typedef boost::shared_ptr<GenericPrior<VALUE> > shared_ptr;
|
||||
typedef VALUE Pose; ///< shortcut to Pose type
|
||||
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
|
||||
Pose measured_; ///< prior mean
|
||||
|
@ -179,6 +180,7 @@ namespace simulated2D {
|
|||
typedef boost::shared_ptr<GenericOdometry<VALUE> > shared_ptr;
|
||||
typedef VALUE Pose; ///< shortcut to Pose type
|
||||
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
|
||||
Pose measured_; ///< odometry measurement
|
||||
|
@ -227,6 +229,7 @@ namespace simulated2D {
|
|||
typedef POSE Pose; ///< shortcut to Pose type
|
||||
typedef LANDMARK Landmark; ///< shortcut to Landmark type
|
||||
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
|
||||
Landmark measured_; ///< Measurement
|
||||
|
|
Loading…
Reference in New Issue