Added SuccessiveLinearizationParams.ordering and BearingRangeFactor in matlab interface
parent
d397139fa9
commit
5b584c3b73
15
gtsam.h
15
gtsam.h
|
@ -1167,6 +1167,7 @@ virtual class NonlinearOptimizerParams {
|
|||
virtual class SuccessiveLinearizationParams : gtsam::NonlinearOptimizerParams {
|
||||
SuccessiveLinearizationParams();
|
||||
|
||||
void setOrdering(const gtsam::Ordering& ordering);
|
||||
bool isMultifrontal() const;
|
||||
bool isSequential() const;
|
||||
bool isCholmod() const;
|
||||
|
@ -1357,16 +1358,22 @@ typedef gtsam::RangeFactor<gtsam::SimpleCamera, gtsam::Point3> RangeFactorSimple
|
|||
typedef gtsam::RangeFactor<gtsam::CalibratedCamera, gtsam::CalibratedCamera> RangeFactorCalibratedCamera;
|
||||
typedef gtsam::RangeFactor<gtsam::SimpleCamera, gtsam::SimpleCamera> RangeFactorSimpleCamera;
|
||||
|
||||
|
||||
#include <gtsam/slam/BearingFactor.h>
|
||||
template<POSE, POINT, ROT>
|
||||
template<POSE, POINT, ROTATION>
|
||||
virtual class BearingFactor : gtsam::NonlinearFactor {
|
||||
BearingFactor(size_t key1, size_t key2, const ROT& measured, const gtsam::noiseModel::Base* noiseModel);
|
||||
BearingFactor(size_t key1, size_t key2, const ROTATION& measured, const gtsam::noiseModel::Base* noiseModel);
|
||||
};
|
||||
|
||||
typedef gtsam::BearingFactor<gtsam::Pose2, gtsam::Point2, gtsam::Rot2> BearingFactor2D;
|
||||
|
||||
|
||||
template<POSE, POINT, ROTATION>
|
||||
virtual class BearingRangeFactor : gtsam::NonlinearFactor {
|
||||
BearingRangeFactor(size_t poseKey, size_t pointKey, const ROTATION& measuredBearing, double measuredRange, const gtsam::noiseModel::Base* noiseModel);
|
||||
};
|
||||
|
||||
typedef gtsam::BearingRangeFactor<gtsam::Pose2, gtsam::Point2, gtsam::Rot2> BearingRangeFactor2D;
|
||||
|
||||
|
||||
#include <gtsam/slam/ProjectionFactor.h>
|
||||
template<POSE, LANDMARK, CALIBRATION>
|
||||
virtual class GenericProjectionFactor : gtsam::NonlinearFactor {
|
||||
|
|
|
@ -78,20 +78,16 @@ public:
|
|||
}
|
||||
|
||||
inline bool isMultifrontal() const {
|
||||
return (linearSolverType == MULTIFRONTAL_CHOLESKY) || (linearSolverType == MULTIFRONTAL_QR);
|
||||
}
|
||||
return (linearSolverType == MULTIFRONTAL_CHOLESKY) || (linearSolverType == MULTIFRONTAL_QR); }
|
||||
|
||||
inline bool isSequential() const {
|
||||
return (linearSolverType == SEQUENTIAL_CHOLESKY) || (linearSolverType == SEQUENTIAL_QR);
|
||||
}
|
||||
return (linearSolverType == SEQUENTIAL_CHOLESKY) || (linearSolverType == SEQUENTIAL_QR); }
|
||||
|
||||
inline bool isCholmod() const {
|
||||
return (linearSolverType == CHOLMOD);
|
||||
}
|
||||
inline bool isCholmod() const { return (linearSolverType == CHOLMOD); }
|
||||
|
||||
inline bool isCG() const {
|
||||
return (linearSolverType == CG);
|
||||
}
|
||||
inline bool isCG() const { return (linearSolverType == CG); }
|
||||
|
||||
void setOrdering(const Ordering& ordering) { this->ordering = ordering; }
|
||||
|
||||
GaussianFactorGraph::Eliminate getEliminationFunction() {
|
||||
switch (linearSolverType) {
|
||||
|
|
|
@ -25,12 +25,12 @@ namespace gtsam {
|
|||
/**
|
||||
* Binary factor for a bearing measurement
|
||||
*/
|
||||
template<class POSE, class POINT, class ROT = typename POSE::Rotation>
|
||||
template<class POSE, class POINT, class ROTATION = typename POSE::Rotation>
|
||||
class BearingFactor: public NoiseModelFactor2<POSE, POINT> {
|
||||
private:
|
||||
|
||||
typedef POSE Pose;
|
||||
typedef ROT Rot;
|
||||
typedef ROTATION Rot;
|
||||
typedef POINT Point;
|
||||
|
||||
typedef BearingFactor<POSE, POINT> This;
|
||||
|
|
|
@ -27,12 +27,12 @@ namespace gtsam {
|
|||
/**
|
||||
* Binary factor for a bearing measurement
|
||||
*/
|
||||
template<class POSE, class POINT>
|
||||
template<class POSE, class POINT, class ROTATION = typename POSE::Rotation>
|
||||
class BearingRangeFactor: public NoiseModelFactor2<POSE, POINT> {
|
||||
private:
|
||||
|
||||
typedef POSE Pose;
|
||||
typedef typename POSE::Rotation Rot;
|
||||
typedef ROTATION Rot;
|
||||
typedef POINT Point;
|
||||
|
||||
typedef BearingRangeFactor<POSE, POINT> This;
|
||||
|
|
Loading…
Reference in New Issue