make noise model default constructors available for serialization
parent
c0798a5097
commit
007022df6f
|
@ -177,17 +177,16 @@ namespace gtsam {
|
||||||
return *sqrt_information_;
|
return *sqrt_information_;
|
||||||
}
|
}
|
||||||
|
|
||||||
protected:
|
|
||||||
|
|
||||||
/** protected constructor takes square root information matrix */
|
|
||||||
Gaussian(size_t dim = 1, const boost::optional<Matrix>& sqrt_information = boost::none) :
|
|
||||||
Base(dim), sqrt_information_(sqrt_information) {
|
|
||||||
}
|
|
||||||
|
|
||||||
public:
|
public:
|
||||||
|
|
||||||
typedef boost::shared_ptr<Gaussian> shared_ptr;
|
typedef boost::shared_ptr<Gaussian> shared_ptr;
|
||||||
|
|
||||||
|
/** constructor takes square root information matrix */
|
||||||
|
Gaussian(size_t dim = 1,
|
||||||
|
const boost::optional<Matrix>& sqrt_information = boost::none)
|
||||||
|
: Base(dim), sqrt_information_(sqrt_information) {}
|
||||||
|
|
||||||
~Gaussian() override {}
|
~Gaussian() override {}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
@ -290,13 +289,13 @@ namespace gtsam {
|
||||||
Vector sigmas_, invsigmas_, precisions_;
|
Vector sigmas_, invsigmas_, precisions_;
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
/** protected constructor - no initializations */
|
|
||||||
Diagonal();
|
|
||||||
|
|
||||||
/** constructor to allow for disabling initialization of invsigmas */
|
/** constructor to allow for disabling initialization of invsigmas */
|
||||||
Diagonal(const Vector& sigmas);
|
Diagonal(const Vector& sigmas);
|
||||||
|
|
||||||
public:
|
public:
|
||||||
|
/** constructor - no initializations, for serialization */
|
||||||
|
Diagonal();
|
||||||
|
|
||||||
typedef boost::shared_ptr<Diagonal> shared_ptr;
|
typedef boost::shared_ptr<Diagonal> shared_ptr;
|
||||||
|
|
||||||
|
@ -387,14 +386,6 @@ namespace gtsam {
|
||||||
// Sigmas are contained in the base class
|
// Sigmas are contained in the base class
|
||||||
Vector mu_; ///< Penalty function weight - needs to be large enough to dominate soft constraints
|
Vector mu_; ///< Penalty function weight - needs to be large enough to dominate soft constraints
|
||||||
|
|
||||||
/**
|
|
||||||
* protected constructor takes sigmas.
|
|
||||||
* prevents any inf values
|
|
||||||
* from appearing in invsigmas or precisions.
|
|
||||||
* mu set to large default value (1000.0)
|
|
||||||
*/
|
|
||||||
Constrained(const Vector& sigmas = Z_1x1);
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Constructor that prevents any inf values
|
* Constructor that prevents any inf values
|
||||||
* from appearing in invsigmas or precisions.
|
* from appearing in invsigmas or precisions.
|
||||||
|
@ -406,6 +397,14 @@ namespace gtsam {
|
||||||
|
|
||||||
typedef boost::shared_ptr<Constrained> shared_ptr;
|
typedef boost::shared_ptr<Constrained> shared_ptr;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* protected constructor takes sigmas.
|
||||||
|
* prevents any inf values
|
||||||
|
* from appearing in invsigmas or precisions.
|
||||||
|
* mu set to large default value (1000.0)
|
||||||
|
*/
|
||||||
|
Constrained(const Vector& sigmas = Z_1x1);
|
||||||
|
|
||||||
~Constrained() override {}
|
~Constrained() override {}
|
||||||
|
|
||||||
/// true if a constrained noise mode, saves slow/clumsy dynamic casting
|
/// true if a constrained noise mode, saves slow/clumsy dynamic casting
|
||||||
|
@ -531,11 +530,11 @@ namespace gtsam {
|
||||||
Isotropic(size_t dim, double sigma) :
|
Isotropic(size_t dim, double sigma) :
|
||||||
Diagonal(Vector::Constant(dim, sigma)),sigma_(sigma),invsigma_(1.0/sigma) {}
|
Diagonal(Vector::Constant(dim, sigma)),sigma_(sigma),invsigma_(1.0/sigma) {}
|
||||||
|
|
||||||
|
public:
|
||||||
|
|
||||||
/* dummy constructor to allow for serialization */
|
/* dummy constructor to allow for serialization */
|
||||||
Isotropic() : Diagonal(Vector1::Constant(1.0)),sigma_(1.0),invsigma_(1.0) {}
|
Isotropic() : Diagonal(Vector1::Constant(1.0)),sigma_(1.0),invsigma_(1.0) {}
|
||||||
|
|
||||||
public:
|
|
||||||
|
|
||||||
~Isotropic() override {}
|
~Isotropic() override {}
|
||||||
|
|
||||||
typedef boost::shared_ptr<Isotropic> shared_ptr;
|
typedef boost::shared_ptr<Isotropic> shared_ptr;
|
||||||
|
@ -592,14 +591,13 @@ namespace gtsam {
|
||||||
* Unit: i.i.d. unit-variance noise on all m dimensions.
|
* Unit: i.i.d. unit-variance noise on all m dimensions.
|
||||||
*/
|
*/
|
||||||
class GTSAM_EXPORT Unit : public Isotropic {
|
class GTSAM_EXPORT Unit : public Isotropic {
|
||||||
protected:
|
|
||||||
|
|
||||||
Unit(size_t dim=1): Isotropic(dim,1.0) {}
|
|
||||||
|
|
||||||
public:
|
public:
|
||||||
|
|
||||||
typedef boost::shared_ptr<Unit> shared_ptr;
|
typedef boost::shared_ptr<Unit> shared_ptr;
|
||||||
|
|
||||||
|
/** constructor for serialization */
|
||||||
|
Unit(size_t dim=1): Isotropic(dim,1.0) {}
|
||||||
|
|
||||||
~Unit() override {}
|
~Unit() override {}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
|
Loading…
Reference in New Issue