added some comments and fixed some formatting
parent
6aed555eef
commit
53d23b96ff
|
@ -6,9 +6,6 @@ if(NOT DEFINED CMAKE_MACOSX_RPATH)
|
|||
set(CMAKE_MACOSX_RPATH 0)
|
||||
endif()
|
||||
|
||||
add_definitions(-Wno-deprecated-declarations)
|
||||
add_definitions(-ftemplate-backtrace-limit=0)
|
||||
|
||||
set(CMAKE_CXX_STANDARD 17)
|
||||
|
||||
# Set the version number for the library
|
||||
|
|
|
@ -92,12 +92,12 @@ public:
|
|||
}
|
||||
|
||||
/// Constructor that will resize a dynamic matrix (unless already correct)
|
||||
OptionalJacobian(Eigen::MatrixXd* dynamic) :
|
||||
map_(nullptr) {
|
||||
if (dynamic) {
|
||||
dynamic->resize(Rows, Cols); // no malloc if correct size
|
||||
OptionalJacobian(Eigen::MatrixXd* dynamic)
|
||||
: map_(nullptr) {
|
||||
if (dynamic) {
|
||||
dynamic->resize(Rows, Cols); // no malloc if correct size
|
||||
usurp(dynamic->data());
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
|
|
|
@ -31,6 +31,7 @@ class ConstantVelocityFactor : public NoiseModelFactorN<NavState, NavState> {
|
|||
|
||||
public:
|
||||
using Base = NoiseModelFactor2<NavState, NavState>;
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
|
||||
public:
|
||||
|
|
|
@ -55,6 +55,7 @@ protected:
|
|||
|
||||
|
||||
public:
|
||||
// Provide access to the Matrix& version of unwhitenedError:
|
||||
using NoiseModelFactor::unwhitenedError;
|
||||
typedef boost::shared_ptr<ExpressionFactor<T> > shared_ptr;
|
||||
|
||||
|
@ -244,6 +245,8 @@ class ExpressionFactorN : public ExpressionFactor<T> {
|
|||
public:
|
||||
static const std::size_t NARY_EXPRESSION_SIZE = sizeof...(Args);
|
||||
using ArrayNKeys = std::array<Key, NARY_EXPRESSION_SIZE>;
|
||||
|
||||
// Provide access to the Matrix& version of unwhitenedError:
|
||||
using ExpressionFactor<T>::unwhitenedError;
|
||||
|
||||
/// Destructor
|
||||
|
|
|
@ -46,6 +46,7 @@ class NonlinearEquality: public NoiseModelFactorN<VALUE> {
|
|||
|
||||
public:
|
||||
typedef VALUE T;
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using NoiseModelFactor1<VALUE>::evaluateError;
|
||||
|
||||
private:
|
||||
|
|
|
@ -247,8 +247,12 @@ public:
|
|||
virtual Vector unwhitenedError(const Values& x, OptionalMatrixVecType H = OptionalMatrixVecNone) const = 0;
|
||||
|
||||
// support taking in the actual vector instead of the pointer as well
|
||||
// to get access to this version of the function from derived classes
|
||||
// one will need to use the "using" keyword and specify that like this:
|
||||
// public:
|
||||
// using NoiseModelFactor::unwhitenedError;
|
||||
Vector unwhitenedError(const Values& x, std::vector<Matrix>& H) const {
|
||||
return unwhitenedError(x, &H);
|
||||
return unwhitenedError(x, &H);
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -593,10 +597,14 @@ protected:
|
|||
virtual Vector evaluateError(const ValueTypes&... x,
|
||||
OptionalMatrixTypeT<ValueTypes>... H) const = 0;
|
||||
|
||||
// if someone uses the evaluateError function by supplying all the optional
|
||||
// If someone uses the evaluateError function by supplying all the optional
|
||||
// arguments then redirect the call to the one which takes pointers
|
||||
// to get access to this version of the function from derived classes
|
||||
// one will need to use the "using" keyword and specify that like this:
|
||||
// public:
|
||||
// using NoiseModelFactorN<list the value types here>::evaluateError;
|
||||
Vector evaluateError(const ValueTypes&... x, MatrixTypeT<ValueTypes>&... H) const {
|
||||
return evaluateError(x..., (&H)...);
|
||||
return evaluateError(x..., (&H)...);
|
||||
}
|
||||
|
||||
/// @}
|
||||
|
@ -619,19 +627,23 @@ protected:
|
|||
*/
|
||||
template <typename... OptionalJacArgs, typename = IndexIsValid<sizeof...(OptionalJacArgs) + 1>>
|
||||
inline Vector evaluateError(const ValueTypes&... x, OptionalJacArgs&&... H) const {
|
||||
// A check to ensure all arguments passed are all either matrices or are all pointers to matrices
|
||||
// A check to ensure all arguments passed are either matrices or are all pointers to matrices
|
||||
constexpr bool are_all_mat = (... && (std::is_same<Matrix, std::decay_t<OptionalJacArgs>>::value));
|
||||
// The pointers can either be of std::nonetype_t or of Matrix* type
|
||||
constexpr bool are_all_ptrs = (... && (std::is_same<OptionalMatrixType, std::decay_t<OptionalJacArgs>>::value ||
|
||||
std::is_same<OptionalNoneType, std::decay_t<OptionalJacArgs>>::value));
|
||||
static_assert((are_all_mat || are_all_ptrs),
|
||||
"Arguments that are passed to the evaluateError function can only be of following the types: Matrix, "
|
||||
"or Matrix*");
|
||||
// if they pass all matrices then we want to pass their pointers instead
|
||||
if constexpr (are_all_mat) {
|
||||
return evaluateError(x..., (&H)...);
|
||||
} else {
|
||||
return evaluateError(x..., std::forward<OptionalJacArgs>(H)..., static_cast<OptionalMatrixType>(OptionalNone));
|
||||
}
|
||||
// if they pass all matrices then we want to pass their pointers instead
|
||||
if constexpr (are_all_mat) {
|
||||
return evaluateError(x..., (&H)...);
|
||||
} else {
|
||||
// If they are pointer version, ensure to cast them all to be Matrix* types
|
||||
// This will ensure any arguments inferred as std::nonetype_t are cast to (Matrix*) nullptr
|
||||
// This guides the compiler to the correct overload which is the one that takes pointers
|
||||
return evaluateError(x..., std::forward<OptionalJacArgs>(H)..., static_cast<OptionalMatrixType>(OptionalNone));
|
||||
}
|
||||
}
|
||||
|
||||
/// @}
|
||||
|
|
|
@ -31,7 +31,8 @@ namespace gtsam {
|
|||
|
||||
public:
|
||||
typedef VALUE T;
|
||||
using NoiseModelFactor1<VALUE>::evaluateError;
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using NoiseModelFactor1<VALUE>::evaluateError;
|
||||
|
||||
private:
|
||||
|
||||
|
|
|
@ -1 +1 @@
|
|||
gtsamAddTestsGlob(nonlinear "test*.cpp" "${tests_exclude}" "gtsam")
|
||||
gtsamAddTestsGlob(nonlinear "test*.cpp" "" "gtsam")
|
||||
|
|
|
@ -65,7 +65,7 @@ struct BearingFactor : public ExpressionFactorN<T, A1, A2> {
|
|||
OptionalMatrixType H1 = OptionalNone, OptionalMatrixType H2 = OptionalNone) const {
|
||||
std::vector<Matrix> Hs(2);
|
||||
const auto &keys = Factor::keys();
|
||||
const Vector error = this->unwhitenedError(
|
||||
const Vector error = unwhitenedError(
|
||||
{{keys[0], genericValue(a1)}, {keys[1], genericValue(a2)}},
|
||||
Hs);
|
||||
if (H1) *H1 = Hs[0];
|
||||
|
|
|
@ -55,7 +55,8 @@ namespace gtsam {
|
|||
VALUE measured_; /** The measurement */
|
||||
|
||||
public:
|
||||
using Base::evaluateError;
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
|
||||
// shorthand for a smart pointer to a factor
|
||||
typedef typename boost::shared_ptr<BetweenFactor> shared_ptr;
|
||||
|
|
|
@ -35,6 +35,7 @@ struct BoundingConstraint1: public NoiseModelFactorN<VALUE> {
|
|||
typedef NoiseModelFactorN<VALUE> Base;
|
||||
typedef boost::shared_ptr<BoundingConstraint1<VALUE> > shared_ptr;
|
||||
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
|
||||
double threshold_;
|
||||
|
@ -106,6 +107,7 @@ struct BoundingConstraint2: public NoiseModelFactorN<VALUE1, VALUE2> {
|
|||
typedef NoiseModelFactorN<VALUE1, VALUE2> Base;
|
||||
typedef boost::shared_ptr<BoundingConstraint2<VALUE1, VALUE2> > shared_ptr;
|
||||
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
|
||||
double threshold_;
|
||||
|
|
|
@ -37,6 +37,7 @@ private:
|
|||
EssentialMatrix measuredE_; /** The measurement is an essential matrix */
|
||||
|
||||
public:
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
|
||||
// shorthand for a smart pointer to a factor
|
||||
|
|
|
@ -38,6 +38,8 @@ class EssentialMatrixFactor : public NoiseModelFactorN<EssentialMatrix> {
|
|||
typedef EssentialMatrixFactor This;
|
||||
|
||||
public:
|
||||
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
/**
|
||||
* Constructor
|
||||
|
@ -235,6 +237,7 @@ class EssentialMatrixFactor3 : public EssentialMatrixFactor2 {
|
|||
Rot3 cRb_; ///< Rotation from body to camera frame
|
||||
|
||||
public:
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
/**
|
||||
* Constructor
|
||||
|
@ -336,6 +339,7 @@ class EssentialMatrixFactor4
|
|||
typedef Eigen::Matrix<double, 2, DimK> JacobianCalibration;
|
||||
|
||||
public:
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
/**
|
||||
* Constructor
|
||||
|
|
|
@ -54,7 +54,10 @@ class FrobeniusPrior : public NoiseModelFactorN<Rot> {
|
|||
Eigen::Matrix<double, Dim, 1> vecM_; ///< vectorized matrix to approximate
|
||||
|
||||
public:
|
||||
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using NoiseModelFactor1<Rot>::evaluateError;
|
||||
|
||||
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
|
||||
|
||||
/// Constructor
|
||||
|
@ -79,6 +82,8 @@ class FrobeniusFactor : public NoiseModelFactorN<Rot, Rot> {
|
|||
enum { Dim = Rot::VectorN2::RowsAtCompileTime };
|
||||
|
||||
public:
|
||||
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using NoiseModelFactor2<Rot, Rot>::evaluateError;
|
||||
/// Constructor
|
||||
FrobeniusFactor(Key j1, Key j2, const SharedNoiseModel& model = nullptr)
|
||||
|
|
|
@ -76,6 +76,9 @@ public:
|
|||
typedef GeneralSFMFactor<CAMERA, LANDMARK> This;///< typedef for this object
|
||||
typedef NoiseModelFactorN<CAMERA, LANDMARK> Base;///< typedef for the base class
|
||||
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;//
|
||||
|
||||
// shorthand for a smart pointer to a factor
|
||||
typedef boost::shared_ptr<This> shared_ptr;
|
||||
|
||||
|
@ -123,7 +126,7 @@ public:
|
|||
|
||||
/** h(x)-z */
|
||||
Vector evaluateError(const CAMERA& camera, const LANDMARK& point,
|
||||
OptionalMatrixType H1=OptionalNone, OptionalMatrixType H2=OptionalNone) const override {
|
||||
OptionalMatrixType H1, OptionalMatrixType H2) const override {
|
||||
try {
|
||||
return camera.project2(point,H1,H2) - measured_;
|
||||
}
|
||||
|
@ -258,10 +261,7 @@ public:
|
|||
|
||||
/** h(x)-z */
|
||||
Vector evaluateError(const Pose3& pose3, const Point3& point, const CALIBRATION &calib,
|
||||
OptionalMatrixType H1=OptionalNone,
|
||||
OptionalMatrixType H2=OptionalNone,
|
||||
OptionalMatrixType H3=OptionalNone) const override
|
||||
{
|
||||
OptionalMatrixType H1, OptionalMatrixType H2, OptionalMatrixType H3) const override {
|
||||
try {
|
||||
Camera camera(pose3,calib);
|
||||
return camera.project(point, H1, H2, H3) - measured_;
|
||||
|
|
|
@ -21,6 +21,7 @@ class GTSAM_EXPORT OrientedPlane3Factor: public NoiseModelFactorN<Pose3, Oriente
|
|||
typedef NoiseModelFactorN<Pose3, OrientedPlane3> Base;
|
||||
|
||||
public:
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using NoiseModelFactor2<Pose3, OrientedPlane3>::evaluateError;
|
||||
/// Constructor
|
||||
OrientedPlane3Factor() {
|
||||
|
@ -55,7 +56,10 @@ class GTSAM_EXPORT OrientedPlane3DirectionPrior : public NoiseModelFactorN<Orien
|
|||
typedef NoiseModelFactorN<OrientedPlane3> Base;
|
||||
|
||||
public:
|
||||
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
|
||||
typedef OrientedPlane3DirectionPrior This;
|
||||
/// Constructor
|
||||
OrientedPlane3DirectionPrior() {
|
||||
|
|
|
@ -25,6 +25,8 @@ public:
|
|||
typedef typename POSE::Translation Translation;
|
||||
typedef typename POSE::Rotation Rotation;
|
||||
|
||||
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
|
||||
GTSAM_CONCEPT_POSE_TYPE(Pose)
|
||||
|
|
|
@ -26,6 +26,8 @@ public:
|
|||
typedef typename POSE::Translation Translation;
|
||||
typedef typename POSE::Rotation Rotation;
|
||||
|
||||
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
|
||||
GTSAM_CONCEPT_POSE_TYPE(Pose)
|
||||
|
|
|
@ -53,6 +53,8 @@ namespace gtsam {
|
|||
|
||||
/// shorthand for base class type
|
||||
typedef NoiseModelFactor2<POSE, LANDMARK> Base;
|
||||
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
|
||||
/// shorthand for this class
|
||||
|
|
|
@ -62,6 +62,8 @@ protected:
|
|||
public:
|
||||
typedef NoiseModelFactorN<POINT, TRANSFORM, POINT> Base;
|
||||
typedef ReferenceFrameFactor<POINT, TRANSFORM> This;
|
||||
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
|
||||
typedef POINT Point;
|
||||
|
|
|
@ -28,6 +28,8 @@ class RotateFactor: public NoiseModelFactorN<Rot3> {
|
|||
typedef RotateFactor This;
|
||||
|
||||
public:
|
||||
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
|
||||
/// Constructor
|
||||
|
|
|
@ -48,9 +48,10 @@ public:
|
|||
typedef boost::shared_ptr<GenericStereoFactor> shared_ptr; ///< typedef for shared pointer to this object
|
||||
typedef POSE CamPose; ///< typedef for Pose Lie Value type
|
||||
|
||||
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
|
||||
|
||||
/**
|
||||
* Default constructor
|
||||
*/
|
||||
|
|
|
@ -61,6 +61,8 @@ public:
|
|||
|
||||
/// shorthand for a smart pointer to a factor
|
||||
using shared_ptr = boost::shared_ptr<This>;
|
||||
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using NoiseModelFactor1<Point3>::evaluateError;
|
||||
|
||||
/// Default constructor
|
||||
|
|
|
@ -34,6 +34,8 @@ protected:
|
|||
double dt_; /// time between measurements
|
||||
|
||||
public:
|
||||
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
|
||||
/** Standard constructor */
|
||||
|
|
|
@ -32,6 +32,8 @@ protected:
|
|||
double h_; // time step
|
||||
|
||||
public:
|
||||
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
|
||||
typedef boost::shared_ptr<PendulumFactor1> shared_ptr;
|
||||
|
@ -81,6 +83,7 @@ protected:
|
|||
|
||||
public:
|
||||
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
|
||||
typedef boost::shared_ptr<PendulumFactor2 > shared_ptr;
|
||||
|
@ -131,6 +134,7 @@ protected:
|
|||
|
||||
public:
|
||||
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
|
||||
typedef boost::shared_ptr<PendulumFactorPk > shared_ptr;
|
||||
|
@ -187,6 +191,7 @@ protected:
|
|||
double alpha_; //! in [0,1], define the mid-point between [q_k,q_{k+1}] for approximation. The sympletic rule above can be obtained as a special case when alpha = 0.
|
||||
|
||||
public:
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
|
||||
typedef boost::shared_ptr<PendulumFactorPk1 > shared_ptr;
|
||||
|
|
|
@ -29,7 +29,9 @@ class Reconstruction : public NoiseModelFactorN<Pose3, Pose3, Vector6> {
|
|||
double h_; // time step
|
||||
typedef NoiseModelFactorN<Pose3, Pose3, Vector6> Base;
|
||||
public:
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
|
||||
Reconstruction(Key gKey1, Key gKey, Key xiKey, double h, double mu = 1000.0) :
|
||||
Base(noiseModel::Constrained::All(6, std::abs(mu)), gKey1, gKey,
|
||||
xiKey), h_(h) {
|
||||
|
@ -89,6 +91,7 @@ class DiscreteEulerPoincareHelicopter : public NoiseModelFactorN<Vector6, Vector
|
|||
typedef NoiseModelFactorN<Vector6, Vector6, Pose3> Base;
|
||||
|
||||
public:
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
|
||||
DiscreteEulerPoincareHelicopter(Key xiKey1, Key xiKey_1, Key gKey,
|
||||
|
|
|
@ -35,6 +35,7 @@ typedef enum {
|
|||
class VelocityConstraint : public gtsam::NoiseModelFactorN<PoseRTV,PoseRTV> {
|
||||
public:
|
||||
typedef gtsam::NoiseModelFactor2<PoseRTV,PoseRTV> Base;
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
|
||||
protected:
|
||||
|
|
|
@ -23,6 +23,7 @@ protected:
|
|||
|
||||
public:
|
||||
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
typedef boost::shared_ptr<VelocityConstraint3 > shared_ptr;
|
||||
|
||||
|
|
|
@ -58,10 +58,11 @@ TEST( Reconstruction, evaluateError) {
|
|||
EXPECT(
|
||||
assert_equal(Z_6x1, constraint.evaluateError(g2, g1, V1_g1, H1, H2, H3), tol));
|
||||
|
||||
std::function<Vector(const Pose3&, const Pose3&, const Vector6&)> f = [&constraint](const Pose3& a1, const Pose3& a2,
|
||||
const Vector6& a3) {
|
||||
std::function<Vector(const Pose3&, const Pose3&, const Vector6&)> f =
|
||||
[&constraint](const Pose3& a1, const Pose3& a2, const Vector6& a3) {
|
||||
return constraint.evaluateError(a1, a2, a3);
|
||||
};
|
||||
|
||||
Matrix numericalH1 = numericalDerivative31(f, g2, g1, V1_g1, 1e-5);
|
||||
|
||||
Matrix numericalH2 = numericalDerivative32(f, g2, g1, V1_g1, 1e-5);
|
||||
|
|
|
@ -228,6 +228,8 @@ public:
|
|||
return err_wh_eq;
|
||||
}
|
||||
|
||||
// A function overload that takes a vector of matrices and passes it to the
|
||||
// function above which uses a pointer to a vector instead.
|
||||
Vector whitenedError(const Values& x, std::vector<Matrix>& H) const {
|
||||
return whitenedError(x, &H);
|
||||
}
|
||||
|
|
|
@ -37,7 +37,8 @@ namespace gtsam {
|
|||
Point3 measured_; /** The measurement */
|
||||
|
||||
public:
|
||||
using Base::evaluateError;
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
|
||||
// shorthand for a smart pointer to a factor
|
||||
typedef boost::shared_ptr<BiasedGPSFactor> shared_ptr;
|
||||
|
|
|
@ -111,6 +111,7 @@ private:
|
|||
|
||||
public:
|
||||
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
|
||||
// shorthand for a smart pointer to a factor
|
||||
|
|
|
@ -109,7 +109,9 @@ private:
|
|||
|
||||
public:
|
||||
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
|
||||
// shorthand for a smart pointer to a factor
|
||||
typedef typename boost::shared_ptr<EquivInertialNavFactor_GlobalVel_NoBias> shared_ptr;
|
||||
|
||||
|
|
|
@ -95,6 +95,7 @@ private:
|
|||
boost::optional<POSE> body_P_sensor_; // The pose of the sensor in the body frame
|
||||
|
||||
public:
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
|
||||
// shorthand for a smart pointer to a factor
|
||||
|
|
|
@ -35,6 +35,7 @@ public:
|
|||
|
||||
/// shorthand for base class type
|
||||
typedef NoiseModelFactor3<POSE, LANDMARK, INVDEPTH> Base;
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
|
||||
/// shorthand for this class
|
||||
|
|
|
@ -35,6 +35,7 @@ public:
|
|||
|
||||
/// shorthand for base class type
|
||||
typedef NoiseModelFactor2<Pose3, Vector6> Base;
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
|
||||
/// shorthand for this class
|
||||
|
|
|
@ -37,6 +37,7 @@ public:
|
|||
|
||||
/// shorthand for base class type
|
||||
typedef NoiseModelFactor2<Pose3, Vector3> Base;
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
|
||||
/// shorthand for this class
|
||||
|
|
|
@ -35,6 +35,7 @@ public:
|
|||
|
||||
/// shorthand for base class type
|
||||
typedef NoiseModelFactor2<Pose3, Vector3> Base;
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
|
||||
/// shorthand for this class
|
||||
|
|
|
@ -40,6 +40,7 @@ class GTSAM_UNSTABLE_EXPORT LocalOrientedPlane3Factor
|
|||
OrientedPlane3 measured_p_;
|
||||
typedef NoiseModelFactorN<Pose3, Pose3, OrientedPlane3> Base;
|
||||
public:
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
/// Constructor
|
||||
LocalOrientedPlane3Factor() {}
|
||||
|
|
|
@ -61,6 +61,7 @@ namespace gtsam {
|
|||
: Base(model, key) {}
|
||||
|
||||
public:
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
|
||||
~PartialPriorFactor() override {}
|
||||
|
|
|
@ -43,6 +43,7 @@ namespace gtsam {
|
|||
GTSAM_CONCEPT_TESTABLE_TYPE(POSE)
|
||||
GTSAM_CONCEPT_POSE_TYPE(POSE)
|
||||
public:
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
|
||||
// shorthand for a smart pointer to a factor
|
||||
|
|
|
@ -40,6 +40,7 @@ namespace gtsam {
|
|||
GTSAM_CONCEPT_TESTABLE_TYPE(POSE)
|
||||
GTSAM_CONCEPT_POSE_TYPE(POSE)
|
||||
public:
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
|
||||
/// shorthand for a smart pointer to a factor
|
||||
|
|
|
@ -29,7 +29,7 @@ class PoseToPointFactor : public NoiseModelFactorN<POSE, POINT> {
|
|||
POINT measured_; /** the point measurement in local coordinates */
|
||||
|
||||
public:
|
||||
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
// shorthand for a smart pointer to a factor
|
||||
typedef boost::shared_ptr<PoseToPointFactor> shared_ptr;
|
||||
|
|
|
@ -46,6 +46,7 @@ namespace gtsam {
|
|||
|
||||
/// shorthand for base class type
|
||||
typedef NoiseModelFactor3<POSE, POSE, LANDMARK> Base;
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
|
||||
/// shorthand for this class
|
||||
|
|
|
@ -45,6 +45,7 @@ class GTSAM_UNSTABLE_EXPORT ProjectionFactorPPPC
|
|||
public:
|
||||
/// shorthand for base class type
|
||||
typedef NoiseModelFactor4<POSE, POSE, LANDMARK, CALIBRATION> Base;
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
|
||||
/// shorthand for this class
|
||||
|
|
|
@ -61,6 +61,7 @@ class GTSAM_UNSTABLE_EXPORT ProjectionFactorRollingShutter
|
|||
public:
|
||||
/// shorthand for base class type
|
||||
typedef NoiseModelFactor3<Pose3, Pose3, Point3> Base;
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
|
||||
/// shorthand for this class
|
||||
|
|
|
@ -34,6 +34,7 @@ private:
|
|||
typedef NoiseModelFactorN<Pose3, Point3> Base;
|
||||
|
||||
public:
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
|
||||
RelativeElevationFactor() : measured_(0.0) {} /* Default constructor */
|
||||
|
|
|
@ -42,7 +42,9 @@ class SmartRangeFactor: public NoiseModelFactor {
|
|||
double variance_; ///< variance on noise
|
||||
|
||||
public:
|
||||
// Provide access to the Matrix& version of unwhitenedError
|
||||
using NoiseModelFactor::unwhitenedError;
|
||||
|
||||
/** Default constructor: don't use directly */
|
||||
SmartRangeFactor() {
|
||||
}
|
||||
|
|
|
@ -37,6 +37,7 @@ private:
|
|||
Point2 measured_; ///< the measurement
|
||||
|
||||
public:
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
|
||||
/// Constructor
|
||||
|
@ -66,6 +67,7 @@ private:
|
|||
Point2 measured_; ///< the measurement
|
||||
|
||||
public:
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
/// Constructor
|
||||
DeltaFactorBase(Key b1, Key i, Key b2, Key j, const Point2& measured,
|
||||
|
@ -119,6 +121,7 @@ private:
|
|||
Pose2 measured_; ///< the measurement
|
||||
|
||||
public:
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
|
||||
/// Constructor
|
||||
|
|
|
@ -245,9 +245,9 @@ namespace gtsam {
|
|||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
Vector whitenedError(const Values& x, std::vector<Matrix>& H) const {
|
||||
return whitenedError(x, &H);
|
||||
}
|
||||
Vector whitenedError(const Values& x, std::vector<Matrix>& H) const {
|
||||
return whitenedError(x, &H);
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
Vector calcIndicatorProb(const Values& x) const {
|
||||
|
|
|
@ -101,6 +101,7 @@ protected:
|
|||
Matrix Q_invsqrt_;
|
||||
|
||||
public:
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
|
||||
NonlinearMotionModel(){}
|
||||
|
@ -246,6 +247,7 @@ protected:
|
|||
Matrix R_invsqrt_; /** The inv sqrt of the measurement error covariance */
|
||||
|
||||
public:
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
NonlinearMeasurementModel(){}
|
||||
|
||||
|
|
|
@ -389,6 +389,7 @@ class TestFactor4 : public NoiseModelFactor4<double, double, double, double> {
|
|||
|
||||
public:
|
||||
typedef NoiseModelFactor4<double, double, double, double> Base;
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
TestFactor4() : Base(noiseModel::Diagonal::Sigmas((Vector(1) << 2.0).finished()), X(1), X(2), X(3), X(4)) {}
|
||||
using Base::NoiseModelFactor4; // inherit constructors
|
||||
|
@ -479,6 +480,7 @@ TEST(NonlinearFactor, NoiseModelFactor4) {
|
|||
class TestFactor5 : public NoiseModelFactor5<double, double, double, double, double> {
|
||||
public:
|
||||
typedef NoiseModelFactor5<double, double, double, double, double> Base;
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
TestFactor5() : Base(noiseModel::Diagonal::Sigmas((Vector(1) << 2.0).finished()), X(1), X(2), X(3), X(4), X(5)) {}
|
||||
|
||||
|
@ -527,6 +529,7 @@ TEST(NonlinearFactor, NoiseModelFactor5) {
|
|||
class TestFactor6 : public NoiseModelFactor6<double, double, double, double, double, double> {
|
||||
public:
|
||||
typedef NoiseModelFactor6<double, double, double, double, double, double> Base;
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
TestFactor6() : Base(noiseModel::Diagonal::Sigmas((Vector(1) << 2.0).finished()), X(1), X(2), X(3), X(4), X(5), X(6)) {}
|
||||
|
||||
|
@ -582,6 +585,7 @@ TEST(NonlinearFactor, NoiseModelFactor6) {
|
|||
class TestFactorN : public NoiseModelFactorN<double, double, double, double> {
|
||||
public:
|
||||
typedef NoiseModelFactorN<double, double, double, double> Base;
|
||||
// Provide access to the Matrix& version of evaluateError:
|
||||
using Base::evaluateError;
|
||||
using Type1 = ValueType<1>; // Test that we can use the ValueType<> template
|
||||
|
||||
|
|
Loading…
Reference in New Issue