correct serialization of base classes
moved all serialize functions to bottom of class declarationrelease/4.3a0
parent
c69d8d9b36
commit
92dbc8910e
|
@ -89,7 +89,7 @@ namespace gtsam {
|
||||||
/**
|
/**
|
||||||
* Check if equal up to specified tolerance
|
* Check if equal up to specified tolerance
|
||||||
*/
|
*/
|
||||||
bool equals(const Cal3_S2& K, double tol) const;
|
bool equals(const Cal3_S2& K, double tol = 10e-9) const;
|
||||||
|
|
||||||
/** friends */
|
/** friends */
|
||||||
friend Matrix Duncalibrate2(const Cal3_S2& K, const Point2& p);
|
friend Matrix Duncalibrate2(const Cal3_S2& K, const Point2& p);
|
||||||
|
|
|
@ -32,13 +32,6 @@ namespace gtsam {
|
||||||
/** Collection of factors */
|
/** Collection of factors */
|
||||||
std::vector<shared_factor> factors_;
|
std::vector<shared_factor> factors_;
|
||||||
|
|
||||||
/** Serialization function */
|
|
||||||
friend class boost::serialization::access;
|
|
||||||
template<class Archive>
|
|
||||||
void serialize(Archive & ar, const unsigned int version) {
|
|
||||||
ar & BOOST_SERIALIZATION_NVP(factors_);
|
|
||||||
}
|
|
||||||
|
|
||||||
public:
|
public:
|
||||||
|
|
||||||
/** STL like, return the iterator pointing to the first factor */
|
/** STL like, return the iterator pointing to the first factor */
|
||||||
|
@ -109,6 +102,14 @@ namespace gtsam {
|
||||||
fg.print();
|
fg.print();
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
};
|
|
||||||
|
|
||||||
|
private:
|
||||||
|
|
||||||
|
/** Serialization function */
|
||||||
|
friend class boost::serialization::access;
|
||||||
|
template<class Archive>
|
||||||
|
void serialize(Archive & ar, const unsigned int version) {
|
||||||
|
ar & BOOST_SERIALIZATION_NVP(factors_);
|
||||||
|
}
|
||||||
|
}; // FactorGraph
|
||||||
} // namespace gtsam
|
} // namespace gtsam
|
||||||
|
|
|
@ -33,23 +33,11 @@ namespace gtsam {
|
||||||
//typedef boost::shared_ptr<LinearFactor> shared_ptr;
|
//typedef boost::shared_ptr<LinearFactor> shared_ptr;
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Nonlinear factor which assume Gaussian noise on a measurement
|
* Nonlinear factor which assumes Gaussian noise on a measurement
|
||||||
* predicted by a non-linear function h
|
* predicted by a non-linear function h.
|
||||||
*/
|
*/
|
||||||
class NonlinearFactor : public Factor
|
class NonlinearFactor : public Factor
|
||||||
{
|
{
|
||||||
private:
|
|
||||||
|
|
||||||
/** Serialization function */
|
|
||||||
friend class boost::serialization::access;
|
|
||||||
template<class Archive>
|
|
||||||
void serialize(Archive & ar, const unsigned int version) {
|
|
||||||
// ar & boost::serialization::base_object<Factor>(*this); // TODO: needed ?
|
|
||||||
ar & BOOST_SERIALIZATION_NVP(z_);
|
|
||||||
ar & BOOST_SERIALIZATION_NVP(sigma_);
|
|
||||||
ar & BOOST_SERIALIZATION_NVP(keys_);
|
|
||||||
}
|
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
|
||||||
Vector z_; // measurement
|
Vector z_; // measurement
|
||||||
|
@ -93,13 +81,27 @@ namespace gtsam {
|
||||||
|
|
||||||
/** dump the information of the factor into a string **/
|
/** dump the information of the factor into a string **/
|
||||||
std::string dump() const{return "";}
|
std::string dump() const{return "";}
|
||||||
};
|
|
||||||
|
private:
|
||||||
|
|
||||||
|
/** Serialization function */
|
||||||
|
friend class boost::serialization::access;
|
||||||
|
template<class Archive>
|
||||||
|
void serialize(Archive & ar, const unsigned int version) {
|
||||||
|
// ar & boost::serialization::base_object<Factor>(*this); // TODO: needed ?
|
||||||
|
ar & BOOST_SERIALIZATION_NVP(z_);
|
||||||
|
ar & BOOST_SERIALIZATION_NVP(sigma_);
|
||||||
|
ar & BOOST_SERIALIZATION_NVP(keys_);
|
||||||
|
}
|
||||||
|
|
||||||
|
}; // NonlinearFactor
|
||||||
|
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/**
|
||||||
/* a Gaussian nonlinear factor that takes 1 parameter */
|
* a Gaussian nonlinear factor that takes 1 parameter
|
||||||
/* ************************************************************************* */
|
* Note: cannot be serialized as contains function pointers
|
||||||
|
* Specialized derived classes could do this
|
||||||
|
*/
|
||||||
class NonlinearFactor1 : public NonlinearFactor {
|
class NonlinearFactor1 : public NonlinearFactor {
|
||||||
public:
|
public:
|
||||||
|
|
||||||
|
@ -130,10 +132,11 @@ namespace gtsam {
|
||||||
std::string dump() const {return "";}
|
std::string dump() const {return "";}
|
||||||
};
|
};
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/**
|
||||||
/* A Gaussian nonlinear factor that takes 2 parameters */
|
* a Gaussian nonlinear factor that takes 2 parameters
|
||||||
/* ************************************************************************* */
|
* Note: cannot be serialized as contains function pointers
|
||||||
|
* Specialized derived classes could do this
|
||||||
|
*/
|
||||||
class NonlinearFactor2 : public NonlinearFactor {
|
class NonlinearFactor2 : public NonlinearFactor {
|
||||||
public:
|
public:
|
||||||
|
|
||||||
|
|
|
@ -19,18 +19,11 @@
|
||||||
|
|
||||||
namespace gtsam {
|
namespace gtsam {
|
||||||
|
|
||||||
|
typedef FactorGraph<NonlinearFactor> BaseFactorGraph;
|
||||||
|
|
||||||
/** Factor Graph Constsiting of non-linear factors */
|
/** Factor Graph Constsiting of non-linear factors */
|
||||||
class NonlinearFactorGraph : public FactorGraph<NonlinearFactor>
|
class NonlinearFactorGraph : public BaseFactorGraph
|
||||||
{
|
{
|
||||||
private:
|
|
||||||
|
|
||||||
/** Serialization function */
|
|
||||||
friend class boost::serialization::access;
|
|
||||||
template<class Archive>
|
|
||||||
void serialize(Archive & ar, const unsigned int version) {
|
|
||||||
ar & boost::serialization::base_object< FactorGraph<NonlinearFactor> >(*this);
|
|
||||||
}
|
|
||||||
|
|
||||||
public: // internal, exposed for testing only, doc in .cpp file
|
public: // internal, exposed for testing only, doc in .cpp file
|
||||||
|
|
||||||
FGConfig iterate(const FGConfig& config, const Ordering& ordering) const;
|
FGConfig iterate(const FGConfig& config, const Ordering& ordering) const;
|
||||||
|
@ -117,5 +110,16 @@ public: // these you will probably want to use
|
||||||
double lambda0,
|
double lambda0,
|
||||||
double lambdaFactor) const ;
|
double lambdaFactor) const ;
|
||||||
|
|
||||||
|
private:
|
||||||
|
|
||||||
|
/** Serialization function */
|
||||||
|
friend class boost::serialization::access;
|
||||||
|
template<class Archive>
|
||||||
|
void serialize(Archive & ar, const unsigned int version) {
|
||||||
|
// do not use BOOST_SERIALIZATION_NVP for this name-value-pair ! It will crash.
|
||||||
|
ar & boost::serialization::make_nvp("BaseFactorGraph",
|
||||||
|
boost::serialization::base_object<BaseFactorGraph>(*this));
|
||||||
|
}
|
||||||
|
|
||||||
};
|
};
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue