adding comments with Frank

release/4.3a0
Duy-Nguyen Ta 2012-06-19 06:05:32 +00:00
parent 0a3d9975f3
commit 350e761ec6
2 changed files with 65 additions and 24 deletions

View File

@ -22,11 +22,17 @@
namespace gtsam { // note, deliberately not in noiseModel namespace
// A useful convenience class to refer to a shared Diagonal model
// There are (somewhat dangerous) constructors from Vector and pair<size_t,double>
// that call Sigmas and Sigma, respectively.
/**
* A useful convenience class to refer to a shared Diagonal model
* There are (somewhat dangerous) constructors from Vector and pair<size_t,double>
* that call Sigmas and Sigma, respectively.
*/
class SharedDiagonal: public noiseModel::Diagonal::shared_ptr {
public:
/// @name Standard Constructors
/// @{
SharedDiagonal() {
}
SharedDiagonal(const noiseModel::Diagonal::shared_ptr& p) :
@ -45,6 +51,10 @@ namespace gtsam { // note, deliberately not in noiseModel namespace
noiseModel::Diagonal::shared_ptr(noiseModel::Diagonal::Sigmas(sigmas)) {
}
/// @}
/// @name Print
/// @{
/// Print
inline void print(const std::string &s) const { (*this)->print(s); }

View File

@ -15,10 +15,16 @@
namespace gtsam { // note, deliberately not in noiseModel namespace
/**
* Just a convenient class to generate shared pointers to a noise model
*/
struct SharedNoiseModel: public noiseModel::Base::shared_ptr {
typedef noiseModel::Base::shared_ptr Base;
/// @name Standard Constructors
/// @{
SharedNoiseModel() {}
SharedNoiseModel(const noiseModel::Robust::shared_ptr& p): Base(p) {}
SharedNoiseModel(const noiseModel::Gaussian::shared_ptr& p): Base(p) {}
@ -27,6 +33,10 @@ namespace gtsam { // note, deliberately not in noiseModel namespace
SharedNoiseModel(const noiseModel::Isotropic::shared_ptr& p): Base(p) {}
SharedNoiseModel(const noiseModel::Unit::shared_ptr& p): Base(p) {}
/// @}
/// @name Dangerous constructors
/// @{
#ifdef GTSAM_MAGIC_GAUSSIAN
SharedNoiseModel(const Matrix& covariance) :
Base(boost::static_pointer_cast<noiseModel::Base>(
@ -45,30 +55,16 @@ namespace gtsam { // note, deliberately not in noiseModel namespace
noiseModel::Isotropic::Sigma(GTSAM_DANGEROUS_GAUSSIAN, s))) {}
#endif
/// @}
/// @name Print
/// @{
/// Print
inline void print(const std::string &s) const { (*this)->print(s); }
// Static syntactic sugar functions to create noisemodels directly
// These should only be used with the Matlab interface
static inline SharedNoiseModel Sigmas(const Vector& sigmas, bool smart=false) {
return noiseModel::Diagonal::Sigmas(sigmas, smart);
}
static inline SharedNoiseModel Sigma(size_t dim, double sigma) {
return noiseModel::Isotropic::Sigma(dim, sigma);
}
static inline SharedNoiseModel Precisions(const Vector& precisions) {
return noiseModel::Diagonal::Precisions(precisions);
}
static inline SharedNoiseModel Precision(size_t dim, double precision) {
return noiseModel::Isotropic::Precision(dim, precision);
}
static inline SharedNoiseModel Unit(size_t dim) {
return noiseModel::Unit::Create(dim);
}
/// @}
/// @name Static syntactic sugar (should only be used with the MATLAB interface)
/// @{
static inline SharedNoiseModel SqrtInformation(const Matrix& R) {
return noiseModel::Gaussian::SqrtInformation(R);
@ -78,6 +74,38 @@ namespace gtsam { // note, deliberately not in noiseModel namespace
return noiseModel::Gaussian::Covariance(covariance, smart);
}
static inline SharedNoiseModel Sigmas(const Vector& sigmas, bool smart=false) {
return noiseModel::Diagonal::Sigmas(sigmas, smart);
}
static inline SharedNoiseModel Variances(const Vector& variances, bool smart=false) {
return noiseModel::Diagonal::Variances(variances, smart);
}
static inline SharedNoiseModel Precisions(const Vector& precisions, bool smart=false) {
return noiseModel::Diagonal::Precisions(precisions, smart);
}
static inline SharedNoiseModel Sigma(size_t dim, double sigma, bool smart=false) {
return noiseModel::Isotropic::Sigma(dim, sigma, smart);
}
static inline SharedNoiseModel Variance(size_t dim, double variance, bool smart=false) {
return noiseModel::Isotropic::Variance(dim, variance, smart);
}
static inline SharedNoiseModel Precision(size_t dim, double precision, bool smart=false) {
return noiseModel::Isotropic::Precision(dim, precision, smart);
}
static inline SharedNoiseModel Unit(size_t dim) {
return noiseModel::Unit::Create(dim);
}
/// @}
/// @name Serialization
/// @{
/** Serialization function */
friend class boost::serialization::access;
template<class ARCHIVE>
@ -85,5 +113,8 @@ namespace gtsam { // note, deliberately not in noiseModel namespace
ar & boost::serialization::make_nvp("SharedNoiseModel",
boost::serialization::base_object<Base>(*this));
}
/// @}
};
}