fixing some mr comments. added new lines

release/4.3a0
kartik arcot 2023-01-11 11:01:49 -08:00
parent 984d2d104f
commit 9c56c73c1a
43 changed files with 78 additions and 18 deletions

View File

@ -3,6 +3,7 @@ class UnaryFactor: public NoiseModelFactor1<Pose2> {
public: public:
using gtsam::NoiseModelFactor1<Pose2>::evaluateError; using gtsam::NoiseModelFactor1<Pose2>::evaluateError;
UnaryFactor(Key j, double x, double y, const SharedNoiseModel& model): UnaryFactor(Key j, double x, double y, const SharedNoiseModel& model):
NoiseModelFactor1<Pose2>(model, j), mx_(x), my_(y) {} NoiseModelFactor1<Pose2>(model, j), mx_(x), my_(y) {}

View File

@ -46,8 +46,7 @@ public:
} }
/// evaluate the error /// evaluate the error
Vector evaluateError(const Pose3& pose, OptionalMatrixType H = Vector evaluateError(const Pose3& pose, OptionalMatrixType H) const override {
OptionalNone) const override {
PinholeCamera<Cal3_S2> camera(pose, *K_); PinholeCamera<Cal3_S2> camera(pose, *K_);
return camera.project(P_, H, OptionalNone, OptionalNone) - p_; return camera.project(P_, H, OptionalNone, OptionalNone) - p_;
} }

View File

@ -71,7 +71,9 @@ class UnaryFactor: public NoiseModelFactorN<Pose2> {
double mx_, my_; double mx_, my_;
public: public:
// Provide access to Matrix& version of evaluateError:
using NoiseModelFactor1<Pose2>::evaluateError; using NoiseModelFactor1<Pose2>::evaluateError;
/// shorthand for a smart pointer to a factor /// shorthand for a smart pointer to a factor
typedef boost::shared_ptr<UnaryFactor> shared_ptr; typedef boost::shared_ptr<UnaryFactor> shared_ptr;

View File

@ -92,8 +92,8 @@ public:
} }
/// Constructor that will resize a dynamic matrix (unless already correct) /// Constructor that will resize a dynamic matrix (unless already correct)
OptionalJacobian(Eigen::MatrixXd* dynamic) OptionalJacobian(Eigen::MatrixXd* dynamic) :
: map_(nullptr) { map_(nullptr) {
if (dynamic) { if (dynamic) {
dynamic->resize(Rows, Cols); // no malloc if correct size dynamic->resize(Rows, Cols); // no malloc if correct size
usurp(dynamic->data()); usurp(dynamic->data());

View File

@ -142,6 +142,7 @@ public:
// Provide access to the Matrix& version of evaluateError: // Provide access to the Matrix& version of evaluateError:
using Base::evaluateError; using Base::evaluateError;
/** Shorthand for a smart pointer to a factor */ /** Shorthand for a smart pointer to a factor */
#if !defined(_MSC_VER) && __GNUC__ == 4 && __GNUC_MINOR__ > 5 #if !defined(_MSC_VER) && __GNUC__ == 4 && __GNUC_MINOR__ > 5
typedef typename boost::shared_ptr<AHRSFactor> shared_ptr; typedef typename boost::shared_ptr<AHRSFactor> shared_ptr;

View File

@ -84,6 +84,7 @@ public:
// Provide access to the Matrix& version of evaluateError: // Provide access to the Matrix& version of evaluateError:
using Base::evaluateError; using Base::evaluateError;
/// shorthand for a smart pointer to a factor /// shorthand for a smart pointer to a factor
typedef boost::shared_ptr<Rot3AttitudeFactor> shared_ptr; typedef boost::shared_ptr<Rot3AttitudeFactor> shared_ptr;

View File

@ -40,6 +40,7 @@ class GTSAM_EXPORT BarometricFactor : public NoiseModelFactorN<Pose3, double> {
public: public:
// Provide access to the Matrix& version of evaluateError: // Provide access to the Matrix& version of evaluateError:
using Base::evaluateError; using Base::evaluateError;
/// shorthand for a smart pointer to a factor /// shorthand for a smart pointer to a factor
typedef boost::shared_ptr<BarometricFactor> shared_ptr; typedef boost::shared_ptr<BarometricFactor> shared_ptr;

View File

@ -268,6 +268,7 @@ private:
PreintegratedCombinedMeasurements _PIM_; PreintegratedCombinedMeasurements _PIM_;
public: public:
// Provide access to Matrix& version of evaluateError:
using Base::evaluateError; using Base::evaluateError;
/** Shorthand for a smart pointer to a factor */ /** Shorthand for a smart pointer to a factor */

View File

@ -44,6 +44,7 @@ public:
// Provide access to the Matrix& version of evaluateError: // Provide access to the Matrix& version of evaluateError:
using Base::evaluateError; using Base::evaluateError;
/// shorthand for a smart pointer to a factor /// shorthand for a smart pointer to a factor
typedef boost::shared_ptr<GPSFactor> shared_ptr; typedef boost::shared_ptr<GPSFactor> shared_ptr;

View File

@ -270,6 +270,9 @@ private:
public: public:
// Provide access to the Matrix& version of evaluateError:
using Base::evaluateError;
/** Default constructor - only use for serialization */ /** Default constructor - only use for serialization */
ImuFactor2() {} ImuFactor2() {}

View File

@ -37,6 +37,7 @@ class MagFactor: public NoiseModelFactorN<Rot2> {
const Point3 bias_; ///< bias const Point3 bias_; ///< bias
public: public:
// Provide access to Matrix& version of evaluateError:
using NoiseModelFactor1<Rot2>::evaluateError; using NoiseModelFactor1<Rot2>::evaluateError;
/** /**
@ -94,8 +95,10 @@ class MagFactor1: public NoiseModelFactorN<Rot3> {
const Point3 bias_; ///< bias const Point3 bias_; ///< bias
public: public:
// Provide access to Matrix& version of evaluateError:
using NoiseModelFactor1<Rot3>::evaluateError; using NoiseModelFactor1<Rot3>::evaluateError;
/** Constructor */ /** Constructor */
MagFactor1(Key key, const Point3& measured, double scale, MagFactor1(Key key, const Point3& measured, double scale,
const Unit3& direction, const Point3& bias, const Unit3& direction, const Point3& bias,
@ -131,8 +134,10 @@ class MagFactor2: public NoiseModelFactorN<Point3, Point3> {
const Rot3 bRn_; ///< The assumed known rotation from nav to body const Rot3 bRn_; ///< The assumed known rotation from nav to body
public: public:
// Provide access to Matrix& version of evaluateError:
using NoiseModelFactor2<Point3, Point3>::evaluateError; using NoiseModelFactor2<Point3, Point3>::evaluateError;
/** Constructor */ /** Constructor */
MagFactor2(Key key1, Key key2, const Point3& measured, const Rot3& nRb, MagFactor2(Key key1, Key key2, const Point3& measured, const Rot3& nRb,
const SharedNoiseModel& model) : const SharedNoiseModel& model) :
@ -172,8 +177,10 @@ class MagFactor3: public NoiseModelFactorN<double, Unit3, Point3> {
const Rot3 bRn_; ///< The assumed known rotation from nav to body const Rot3 bRn_; ///< The assumed known rotation from nav to body
public: public:
// Provide access to Matrix& version of evaluateError:
using NoiseModelFactor3<double, Unit3, Point3>::evaluateError; using NoiseModelFactor3<double, Unit3, Point3>::evaluateError;
/** Constructor */ /** Constructor */
MagFactor3(Key key1, Key key2, Key key3, const Point3& measured, MagFactor3(Key key1, Key key2, Key key3, const Point3& measured,
const Rot3& nRb, const SharedNoiseModel& model) : const Rot3& nRb, const SharedNoiseModel& model) :

View File

@ -52,6 +52,7 @@ class MagPoseFactor: public NoiseModelFactorN<POSE> {
// Provide access to the Matrix& version of evaluateError: // Provide access to the Matrix& version of evaluateError:
using Base::evaluateError; using Base::evaluateError;
~MagPoseFactor() override {} ~MagPoseFactor() override {}
/// Default constructor - only use for serialization. /// Default constructor - only use for serialization.

View File

@ -343,7 +343,8 @@ protected:
ExpressionFactor2() {} ExpressionFactor2() {}
/// Constructor takes care of keys, but still need to call initialize /// Constructor takes care of keys, but still need to call initialize
ExpressionFactor2(Key key1, Key key2, const SharedNoiseModel& noiseModel, const T& measurement) ExpressionFactor2(Key key1, Key key2, const SharedNoiseModel& noiseModel,
const T &measurement)
: ExpressionFactorN<T, A1, A2>({key1, key2}, noiseModel, measurement) {} : ExpressionFactorN<T, A1, A2>({key1, key2}, noiseModel, measurement) {}
}; };
// ExpressionFactor2 // ExpressionFactor2

View File

@ -67,6 +67,7 @@ class FunctorizedFactor : public NoiseModelFactorN<T> {
public: public:
// Provide access to the Matrix& version of evaluateError: // Provide access to the Matrix& version of evaluateError:
using Base::evaluateError; using Base::evaluateError;
/** default constructor - only use for serialization */ /** default constructor - only use for serialization */
FunctorizedFactor() {} FunctorizedFactor() {}
@ -169,6 +170,7 @@ class FunctorizedFactor2 : public NoiseModelFactorN<T1, T2> {
public: public:
// Provide access to the Matrix& version of evaluateError: // Provide access to the Matrix& version of evaluateError:
using Base::evaluateError; using Base::evaluateError;
/** default constructor - only use for serialization */ /** default constructor - only use for serialization */
FunctorizedFactor2() {} FunctorizedFactor2() {}

View File

@ -209,6 +209,8 @@ class NonlinearEquality1: public NoiseModelFactorN<VALUE> {
public: public:
typedef VALUE X; typedef VALUE X;
// Provide access to Matrix& version of evaluateError:
using NoiseModelFactor1<VALUE>::evaluateError; using NoiseModelFactor1<VALUE>::evaluateError;
protected: protected:
@ -308,6 +310,7 @@ class NonlinearEquality2 : public NoiseModelFactorN<T, T> {
// Provide access to the Matrix& version of evaluateError: // Provide access to the Matrix& version of evaluateError:
using Base::evaluateError; using Base::evaluateError;
/** /**
* Constructor * Constructor
* @param key1 the key for the first unknown variable to be constrained * @param key1 the key for the first unknown variable to be constrained

View File

@ -32,7 +32,8 @@ namespace gtsam {
public: public:
typedef VALUE T; typedef VALUE T;
// Provide access to the Matrix& version of evaluateError: // Provide access to the Matrix& version of evaluateError:
using NoiseModelFactor1<VALUE>::evaluateError; using NoiseModelFactor1<VALUE>::evaluateError;
private: private:
@ -113,10 +114,10 @@ namespace gtsam {
ar & BOOST_SERIALIZATION_NVP(prior_); ar & BOOST_SERIALIZATION_NVP(prior_);
} }
// Alignment, see https://eigen.tuxfamily.org/dox/group__TopicStructHavingEigenMembers.html // Alignment, see https://eigen.tuxfamily.org/dox/group__TopicStructHavingEigenMembers.html
enum { NeedsToAlign = (sizeof(T) % 16) == 0 }; enum { NeedsToAlign = (sizeof(T) % 16) == 0 };
public: public:
GTSAM_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) GTSAM_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign)
}; };
/// traits /// traits

View File

@ -42,7 +42,9 @@ class GTSAM_EXPORT ShonanFactor : public NoiseModelFactorN<SOn, SOn> {
using Rot = typename std::conditional<d == 2, Rot2, Rot3>::type; using Rot = typename std::conditional<d == 2, Rot2, Rot3>::type;
public: public:
// Provide access to the Matrix& version of evaluateError:
using NoiseModelFactor2<SOn, SOn>::evaluateError; using NoiseModelFactor2<SOn, SOn>::evaluateError;
/// @name Constructor /// @name Constructor
/// @{ /// @{

View File

@ -45,7 +45,9 @@ class TranslationFactor : public NoiseModelFactorN<Point3, Point3> {
Point3 measured_w_aZb_; Point3 measured_w_aZb_;
public: public:
// Provide access to the Matrix& version of evaluateError:
using NoiseModelFactor2<Point3, Point3>::evaluateError; using NoiseModelFactor2<Point3, Point3>::evaluateError;
/// default constructor /// default constructor
TranslationFactor() {} TranslationFactor() {}

View File

@ -41,6 +41,7 @@ class EssentialMatrixFactor : public NoiseModelFactorN<EssentialMatrix> {
// Provide access to the Matrix& version of evaluateError: // Provide access to the Matrix& version of evaluateError:
using Base::evaluateError; using Base::evaluateError;
/** /**
* Constructor * Constructor
* @param key Essential Matrix variable key * @param key Essential Matrix variable key
@ -119,6 +120,7 @@ class EssentialMatrixFactor2
public: public:
// Provide access to the Matrix& version of evaluateError: // Provide access to the Matrix& version of evaluateError:
using Base::evaluateError; using Base::evaluateError;
/** /**
* Constructor * Constructor
* @param key1 Essential Matrix variable key * @param key1 Essential Matrix variable key
@ -240,6 +242,7 @@ class EssentialMatrixFactor3 : public EssentialMatrixFactor2 {
public: public:
// Provide access to the Matrix& version of evaluateError: // Provide access to the Matrix& version of evaluateError:
using Base::evaluateError; using Base::evaluateError;
/** /**
* Constructor * Constructor
* @param key1 Essential Matrix variable key * @param key1 Essential Matrix variable key
@ -342,6 +345,7 @@ class EssentialMatrixFactor4
public: public:
// Provide access to the Matrix& version of evaluateError: // Provide access to the Matrix& version of evaluateError:
using Base::evaluateError; using Base::evaluateError;
/** /**
* Constructor * Constructor
* @param keyE Essential Matrix (from camera B to A) variable key * @param keyE Essential Matrix (from camera B to A) variable key

View File

@ -85,6 +85,7 @@ class FrobeniusFactor : public NoiseModelFactorN<Rot, Rot> {
// Provide access to the Matrix& version of evaluateError: // Provide access to the Matrix& version of evaluateError:
using NoiseModelFactor2<Rot, Rot>::evaluateError; using NoiseModelFactor2<Rot, Rot>::evaluateError;
/// Constructor /// Constructor
FrobeniusFactor(Key j1, Key j2, const SharedNoiseModel& model = nullptr) FrobeniusFactor(Key j1, Key j2, const SharedNoiseModel& model = nullptr)
: NoiseModelFactorN<Rot, Rot>(ConvertNoiseModel(model, Dim), j1, : NoiseModelFactorN<Rot, Rot>(ConvertNoiseModel(model, Dim), j1,
@ -113,7 +114,9 @@ class FrobeniusBetweenFactor : public NoiseModelFactorN<Rot, Rot> {
enum { Dim = Rot::VectorN2::RowsAtCompileTime }; enum { Dim = Rot::VectorN2::RowsAtCompileTime };
public: public:
// Provide access to the Matrix& version of evaluateError:
using NoiseModelFactor2<Rot, Rot>::evaluateError; using NoiseModelFactor2<Rot, Rot>::evaluateError;
EIGEN_MAKE_ALIGNED_OPERATOR_NEW EIGEN_MAKE_ALIGNED_OPERATOR_NEW
/// @name Constructor /// @name Constructor

View File

@ -77,7 +77,7 @@ public:
typedef NoiseModelFactorN<CAMERA, LANDMARK> Base;///< typedef for the base class typedef NoiseModelFactorN<CAMERA, LANDMARK> Base;///< typedef for the base class
// Provide access to the Matrix& version of evaluateError: // Provide access to the Matrix& version of evaluateError:
using Base::evaluateError;// using Base::evaluateError;
// shorthand for a smart pointer to a factor // shorthand for a smart pointer to a factor
typedef boost::shared_ptr<This> shared_ptr; typedef boost::shared_ptr<This> shared_ptr;

View File

@ -23,6 +23,7 @@ class GTSAM_EXPORT OrientedPlane3Factor: public NoiseModelFactorN<Pose3, Oriente
public: public:
// Provide access to the Matrix& version of evaluateError: // Provide access to the Matrix& version of evaluateError:
using NoiseModelFactor2<Pose3, OrientedPlane3>::evaluateError; using NoiseModelFactor2<Pose3, OrientedPlane3>::evaluateError;
/// Constructor /// Constructor
OrientedPlane3Factor() { OrientedPlane3Factor() {
} }

View File

@ -25,7 +25,6 @@ public:
typedef typename POSE::Translation Translation; typedef typename POSE::Translation Translation;
typedef typename POSE::Rotation Rotation; typedef typename POSE::Rotation Rotation;
// Provide access to the Matrix& version of evaluateError: // Provide access to the Matrix& version of evaluateError:
using Base::evaluateError; using Base::evaluateError;

View File

@ -26,7 +26,6 @@ public:
typedef typename POSE::Translation Translation; typedef typename POSE::Translation Translation;
typedef typename POSE::Rotation Rotation; typedef typename POSE::Rotation Rotation;
// Provide access to the Matrix& version of evaluateError: // Provide access to the Matrix& version of evaluateError:
using Base::evaluateError; using Base::evaluateError;

View File

@ -48,7 +48,6 @@ public:
typedef boost::shared_ptr<GenericStereoFactor> shared_ptr; ///< typedef for shared pointer to this object typedef boost::shared_ptr<GenericStereoFactor> shared_ptr; ///< typedef for shared pointer to this object
typedef POSE CamPose; ///< typedef for Pose Lie Value type typedef POSE CamPose; ///< typedef for Pose Lie Value type
// Provide access to the Matrix& version of evaluateError: // Provide access to the Matrix& version of evaluateError:
using Base::evaluateError; using Base::evaluateError;

View File

@ -25,6 +25,7 @@ public:
// Provide access to the Matrix& version of evaluateError: // Provide access to the Matrix& version of evaluateError:
using Base::evaluateError; using Base::evaluateError;
typedef boost::shared_ptr<VelocityConstraint3 > shared_ptr; typedef boost::shared_ptr<VelocityConstraint3 > shared_ptr;
///TODO: comment ///TODO: comment

View File

@ -86,7 +86,7 @@ Pose3Upright Pose3Upright::inverse(OptionalJacobian<4, 4> H1) const {
return Pose3Upright(T_.inverse(), -z_); return Pose3Upright(T_.inverse(), -z_);
} }
OptionalJacobian<3, 3>::Jacobian H3x3; OptionalJacobian<3, 3>::Jacobian H3x3;
// TODO: Could not use reference to a view into H1 and reuse memory // TODO(kartikarcot): Could not use reference to a view into H1 and reuse memory
// Eigen::Ref<Eigen::Matrix<double, 3, 3>> H3x3 = H1->topLeftCorner(3,3); // Eigen::Ref<Eigen::Matrix<double, 3, 3>> H3x3 = H1->topLeftCorner(3,3);
Pose3Upright result(T_.inverse(H3x3), -z_); Pose3Upright result(T_.inverse(H3x3), -z_);
Matrix H1_ = -I_4x4; Matrix H1_ = -I_4x4;
@ -102,7 +102,7 @@ Pose3Upright Pose3Upright::compose(const Pose3Upright& p2,
if (!H1 && !H2) if (!H1 && !H2)
return Pose3Upright(T_.compose(p2.T_), z_ + p2.z_); return Pose3Upright(T_.compose(p2.T_), z_ + p2.z_);
// TODO: Could not use reference to a view into H1 and reuse memory // TODO(kartikarcot): Could not use reference to a view into H1 and reuse memory
OptionalJacobian<3, 3>::Jacobian H3x3; OptionalJacobian<3, 3>::Jacobian H3x3;
Pose3Upright result(T_.compose(p2.T_, H3x3), z_ + p2.z_); Pose3Upright result(T_.compose(p2.T_, H3x3), z_ + p2.z_);
if (H1) { if (H1) {
@ -121,7 +121,7 @@ Pose3Upright Pose3Upright::between(const Pose3Upright& p2,
if (!H1 && !H2) if (!H1 && !H2)
return Pose3Upright(T_.between(p2.T_), p2.z_ - z_); return Pose3Upright(T_.between(p2.T_), p2.z_ - z_);
// TODO: Could not use reference to a view into H1 and H2 to reuse memory // TODO(kartikarcot): Could not use reference to a view into H1 and H2 to reuse memory
OptionalJacobian<3, 3>::Jacobian H3x3_1, H3x3_2; OptionalJacobian<3, 3>::Jacobian H3x3_1, H3x3_2;
Pose3Upright result(T_.between(p2.T_, H3x3_1, H3x3_2), p2.z_ - z_); Pose3Upright result(T_.between(p2.T_, H3x3_1, H3x3_2), p2.z_ - z_);
if (H1) { if (H1) {

View File

@ -114,6 +114,7 @@ public:
// Provide access to the Matrix& version of evaluateError: // Provide access to the Matrix& version of evaluateError:
using Base::evaluateError; using Base::evaluateError;
// shorthand for a smart pointer to a factor // shorthand for a smart pointer to a factor
typedef typename boost::shared_ptr<EquivInertialNavFactor_GlobalVel> shared_ptr; typedef typename boost::shared_ptr<EquivInertialNavFactor_GlobalVel> shared_ptr;

View File

@ -112,6 +112,7 @@ public:
// Provide access to the Matrix& version of evaluateError: // Provide access to the Matrix& version of evaluateError:
using Base::evaluateError; using Base::evaluateError;
// shorthand for a smart pointer to a factor // shorthand for a smart pointer to a factor
typedef typename boost::shared_ptr<EquivInertialNavFactor_GlobalVel_NoBias> shared_ptr; typedef typename boost::shared_ptr<EquivInertialNavFactor_GlobalVel_NoBias> shared_ptr;

View File

@ -56,6 +56,7 @@ public:
// Provide access to the Matrix& version of evaluateError: // Provide access to the Matrix& version of evaluateError:
using Base::evaluateError; using Base::evaluateError;
// shorthand for a smart pointer to a factor // shorthand for a smart pointer to a factor
typedef typename boost::shared_ptr<GaussMarkov1stOrderFactor> shared_ptr; typedef typename boost::shared_ptr<GaussMarkov1stOrderFactor> shared_ptr;

View File

@ -98,6 +98,7 @@ public:
// Provide access to the Matrix& version of evaluateError: // Provide access to the Matrix& version of evaluateError:
using Base::evaluateError; using Base::evaluateError;
// shorthand for a smart pointer to a factor // shorthand for a smart pointer to a factor
typedef typename boost::shared_ptr<InertialNavFactor_GlobalVelocity> shared_ptr; typedef typename boost::shared_ptr<InertialNavFactor_GlobalVelocity> shared_ptr;

View File

@ -38,6 +38,7 @@ public:
// Provide access to the Matrix& version of evaluateError: // Provide access to the Matrix& version of evaluateError:
using Base::evaluateError; using Base::evaluateError;
/// shorthand for this class /// shorthand for this class
typedef InvDepthFactor3<POSE, LANDMARK, INVDEPTH> This; typedef InvDepthFactor3<POSE, LANDMARK, INVDEPTH> This;

View File

@ -38,6 +38,7 @@ public:
// Provide access to the Matrix& version of evaluateError: // Provide access to the Matrix& version of evaluateError:
using Base::evaluateError; using Base::evaluateError;
/// shorthand for this class /// shorthand for this class
typedef InvDepthFactorVariant1 This; typedef InvDepthFactorVariant1 This;

View File

@ -40,6 +40,7 @@ public:
// Provide access to the Matrix& version of evaluateError: // Provide access to the Matrix& version of evaluateError:
using Base::evaluateError; using Base::evaluateError;
/// shorthand for this class /// shorthand for this class
typedef InvDepthFactorVariant2 This; typedef InvDepthFactorVariant2 This;

View File

@ -38,6 +38,7 @@ public:
// Provide access to the Matrix& version of evaluateError: // Provide access to the Matrix& version of evaluateError:
using Base::evaluateError; using Base::evaluateError;
/// shorthand for this class /// shorthand for this class
typedef InvDepthFactorVariant3a This; typedef InvDepthFactorVariant3a This;

View File

@ -42,6 +42,7 @@ class GTSAM_UNSTABLE_EXPORT LocalOrientedPlane3Factor
public: public:
// Provide access to the Matrix& version of evaluateError: // Provide access to the Matrix& version of evaluateError:
using Base::evaluateError; using Base::evaluateError;
/// Constructor /// Constructor
LocalOrientedPlane3Factor() {} LocalOrientedPlane3Factor() {}

View File

@ -31,6 +31,7 @@ class PoseToPointFactor : public NoiseModelFactorN<POSE, POINT> {
public: public:
// Provide access to the Matrix& version of evaluateError: // Provide access to the Matrix& version of evaluateError:
using Base::evaluateError; using Base::evaluateError;
// shorthand for a smart pointer to a factor // shorthand for a smart pointer to a factor
typedef boost::shared_ptr<PoseToPointFactor> shared_ptr; typedef boost::shared_ptr<PoseToPointFactor> shared_ptr;

View File

@ -64,6 +64,7 @@ class GTSAM_UNSTABLE_EXPORT ProjectionFactorRollingShutter
// Provide access to the Matrix& version of evaluateError: // Provide access to the Matrix& version of evaluateError:
using Base::evaluateError; using Base::evaluateError;
/// shorthand for this class /// shorthand for this class
typedef ProjectionFactorRollingShutter This; typedef ProjectionFactorRollingShutter This;

View File

@ -69,6 +69,7 @@ private:
public: public:
// Provide access to the Matrix& version of evaluateError: // Provide access to the Matrix& version of evaluateError:
using Base::evaluateError; using Base::evaluateError;
/// Constructor /// Constructor
DeltaFactorBase(Key b1, Key i, Key b2, Key j, const Point2& measured, DeltaFactorBase(Key b1, Key i, Key b2, Key j, const Point2& measured,
const SharedNoiseModel& model) : const SharedNoiseModel& model) :

View File

@ -106,7 +106,9 @@ namespace simulated2DOriented {
Pose2 measured_; ///< Between measurement for odometry factor Pose2 measured_; ///< Between measurement for odometry factor
typedef GenericOdometry<VALUE> This; typedef GenericOdometry<VALUE> This;
using NoiseModelFactor2<VALUE, VALUE>::evaluateError;
// Provide access to the Matrix& version of evaluateError:
using NoiseModelFactor2<VALUE, VALUE>::evaluateError;
/** /**
* Creates an odometry factor between two poses * Creates an odometry factor between two poses

View File

@ -329,7 +329,9 @@ inline Matrix H(const Point2& v) {
struct UnaryFactor: public gtsam::NoiseModelFactorN<Point2> { struct UnaryFactor: public gtsam::NoiseModelFactorN<Point2> {
// Provide access to the Matrix& version of evaluateError:
using gtsam::NoiseModelFactor1<Point2>::evaluateError; using gtsam::NoiseModelFactor1<Point2>::evaluateError;
Point2 z_; Point2 z_;
UnaryFactor(const Point2& z, const SharedNoiseModel& model, Key key) : UnaryFactor(const Point2& z, const SharedNoiseModel& model, Key key) :

View File

@ -249,6 +249,7 @@ protected:
public: public:
// Provide access to the Matrix& version of evaluateError: // Provide access to the Matrix& version of evaluateError:
using Base::evaluateError; using Base::evaluateError;
NonlinearMeasurementModel(){} NonlinearMeasurementModel(){}
NonlinearMeasurementModel(const Symbol& TestKey, Vector z) : NonlinearMeasurementModel(const Symbol& TestKey, Vector z) :

View File

@ -337,8 +337,11 @@ class TestFactor1 : public NoiseModelFactor1<double> {
public: public:
typedef NoiseModelFactor1<double> Base; typedef NoiseModelFactor1<double> Base;
// Provide access to the Matrix& version of evaluateError:
using Base::evaluateError; using Base::evaluateError;
TestFactor1() : Base(noiseModel::Diagonal::Sigmas(Vector1(2.0)), L(1)) {} TestFactor1() : Base(noiseModel::Diagonal::Sigmas(Vector1(2.0)), L(1)) {}
// Provide access to the Matrix& version of evaluateError:
using Base::NoiseModelFactor1; // inherit constructors using Base::NoiseModelFactor1; // inherit constructors
Vector evaluateError(const double& x1, OptionalMatrixType H1) const override { Vector evaluateError(const double& x1, OptionalMatrixType H1) const override {
@ -391,7 +394,9 @@ class TestFactor4 : public NoiseModelFactor4<double, double, double, double> {
typedef NoiseModelFactor4<double, double, double, double> Base; typedef NoiseModelFactor4<double, double, double, double> Base;
// Provide access to the Matrix& version of evaluateError: // Provide access to the Matrix& version of evaluateError:
using Base::evaluateError; using Base::evaluateError;
TestFactor4() : Base(noiseModel::Diagonal::Sigmas((Vector(1) << 2.0).finished()), X(1), X(2), X(3), X(4)) {} TestFactor4() : Base(noiseModel::Diagonal::Sigmas((Vector(1) << 2.0).finished()), X(1), X(2), X(3), X(4)) {}
// Provide access to the Matrix& version of evaluateError:
using Base::NoiseModelFactor4; // inherit constructors using Base::NoiseModelFactor4; // inherit constructors
Vector Vector
@ -482,6 +487,7 @@ public:
typedef NoiseModelFactor5<double, double, double, double, double> Base; typedef NoiseModelFactor5<double, double, double, double, double> Base;
// Provide access to the Matrix& version of evaluateError: // Provide access to the Matrix& version of evaluateError:
using Base::evaluateError; using Base::evaluateError;
TestFactor5() : Base(noiseModel::Diagonal::Sigmas((Vector(1) << 2.0).finished()), X(1), X(2), X(3), X(4), X(5)) {} TestFactor5() : Base(noiseModel::Diagonal::Sigmas((Vector(1) << 2.0).finished()), X(1), X(2), X(3), X(4), X(5)) {}
Vector Vector
@ -531,6 +537,7 @@ public:
typedef NoiseModelFactor6<double, double, double, double, double, double> Base; typedef NoiseModelFactor6<double, double, double, double, double, double> Base;
// Provide access to the Matrix& version of evaluateError: // Provide access to the Matrix& version of evaluateError:
using Base::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)) {} TestFactor6() : Base(noiseModel::Diagonal::Sigmas((Vector(1) << 2.0).finished()), X(1), X(2), X(3), X(4), X(5), X(6)) {}
Vector Vector
@ -587,6 +594,7 @@ public:
typedef NoiseModelFactorN<double, double, double, double> Base; typedef NoiseModelFactorN<double, double, double, double> Base;
// Provide access to the Matrix& version of evaluateError: // Provide access to the Matrix& version of evaluateError:
using Base::evaluateError; using Base::evaluateError;
using Type1 = ValueType<1>; // Test that we can use the ValueType<> template using Type1 = ValueType<1>; // Test that we can use the ValueType<> template
TestFactorN() : Base(noiseModel::Diagonal::Sigmas((Vector(1) << 2.0).finished()), X(1), X(2), X(3), X(4)) {} TestFactorN() : Base(noiseModel::Diagonal::Sigmas((Vector(1) << 2.0).finished()), X(1), X(2), X(3), X(4)) {}