Merged in fix/matlab_tests (pull request #361)
close issue #403 close issue #402 close issue #398 close issue #397 close issue #395 close issue #305 close issue #282 close issue #16 Fix/matlab tests Approved-by: Mike Sheffler <msheffler@toyon.com>release/4.3a0
commit
b5a878d2af
12
gtsam.h
12
gtsam.h
|
@ -228,6 +228,12 @@ virtual class Value {
|
||||||
size_t dim() const;
|
size_t dim() const;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
#include <gtsam/base/GenericValue.h>
|
||||||
|
template<T = {Vector, gtsam::Point2, gtsam::Point3, gtsam::Pose2, gtsam::Pose3, gtsam::Rot2}>
|
||||||
|
virtual class GenericValue : gtsam::Value {
|
||||||
|
void serializable() const;
|
||||||
|
};
|
||||||
|
|
||||||
#include <gtsam/base/deprecated/LieScalar.h>
|
#include <gtsam/base/deprecated/LieScalar.h>
|
||||||
class LieScalar {
|
class LieScalar {
|
||||||
// Standard constructors
|
// Standard constructors
|
||||||
|
@ -2259,6 +2265,9 @@ virtual class NonlinearEquality : gtsam::NoiseModelFactor {
|
||||||
template<POSE, POINT>
|
template<POSE, POINT>
|
||||||
virtual class RangeFactor : gtsam::NoiseModelFactor {
|
virtual class RangeFactor : gtsam::NoiseModelFactor {
|
||||||
RangeFactor(size_t key1, size_t key2, double measured, const gtsam::noiseModel::Base* noiseModel);
|
RangeFactor(size_t key1, size_t key2, double measured, const gtsam::noiseModel::Base* noiseModel);
|
||||||
|
|
||||||
|
// enabling serialization functionality
|
||||||
|
void serialize() const;
|
||||||
};
|
};
|
||||||
|
|
||||||
typedef gtsam::RangeFactor<gtsam::Pose2, gtsam::Point2> RangeFactorPosePoint2;
|
typedef gtsam::RangeFactor<gtsam::Pose2, gtsam::Point2> RangeFactorPosePoint2;
|
||||||
|
@ -2275,6 +2284,9 @@ typedef gtsam::RangeFactor<gtsam::SimpleCamera, gtsam::SimpleCamera> RangeFactor
|
||||||
template<POSE, POINT>
|
template<POSE, POINT>
|
||||||
virtual class RangeFactorWithTransform : gtsam::NoiseModelFactor {
|
virtual class RangeFactorWithTransform : gtsam::NoiseModelFactor {
|
||||||
RangeFactorWithTransform(size_t key1, size_t key2, double measured, const gtsam::noiseModel::Base* noiseModel, const POSE& body_T_sensor);
|
RangeFactorWithTransform(size_t key1, size_t key2, double measured, const gtsam::noiseModel::Base* noiseModel, const POSE& body_T_sensor);
|
||||||
|
|
||||||
|
// enabling serialization functionality
|
||||||
|
void serialize() const;
|
||||||
};
|
};
|
||||||
|
|
||||||
typedef gtsam::RangeFactorWithTransform<gtsam::Pose2, gtsam::Point2> RangeFactorWithTransformPosePoint2;
|
typedef gtsam::RangeFactorWithTransform<gtsam::Pose2, gtsam::Point2> RangeFactorWithTransformPosePoint2;
|
||||||
|
|
|
@ -24,7 +24,6 @@
|
||||||
#include <string>
|
#include <string>
|
||||||
|
|
||||||
// includes for standard serialization types
|
// includes for standard serialization types
|
||||||
#include <boost/serialization/export.hpp>
|
|
||||||
#include <boost/serialization/optional.hpp>
|
#include <boost/serialization/optional.hpp>
|
||||||
#include <boost/serialization/shared_ptr.hpp>
|
#include <boost/serialization/shared_ptr.hpp>
|
||||||
#include <boost/serialization/vector.hpp>
|
#include <boost/serialization/vector.hpp>
|
||||||
|
@ -39,6 +38,7 @@
|
||||||
#include <boost/archive/xml_oarchive.hpp>
|
#include <boost/archive/xml_oarchive.hpp>
|
||||||
#include <boost/archive/binary_iarchive.hpp>
|
#include <boost/archive/binary_iarchive.hpp>
|
||||||
#include <boost/archive/binary_oarchive.hpp>
|
#include <boost/archive/binary_oarchive.hpp>
|
||||||
|
#include <boost/serialization/export.hpp>
|
||||||
|
|
||||||
namespace gtsam {
|
namespace gtsam {
|
||||||
|
|
||||||
|
|
|
@ -266,6 +266,13 @@ class ExpressionFactor2 : public ExpressionFactor<T> {
|
||||||
virtual Expression<T> expression() const {
|
virtual Expression<T> expression() const {
|
||||||
return expression(this->keys_[0], this->keys_[1]);
|
return expression(this->keys_[0], this->keys_[1]);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
friend class boost::serialization::access;
|
||||||
|
template <class ARCHIVE>
|
||||||
|
void serialize(ARCHIVE& ar, const unsigned int /*version*/) {
|
||||||
|
ar& boost::serialization::make_nvp(
|
||||||
|
"ExpressionFactor", boost::serialization::base_object<ExpressionFactor<T> >(*this));
|
||||||
|
}
|
||||||
};
|
};
|
||||||
// ExpressionFactor2
|
// ExpressionFactor2
|
||||||
|
|
||||||
|
|
|
@ -60,6 +60,14 @@ struct BearingFactor : public ExpressionFactor2<T, A1, A2> {
|
||||||
std::cout << s << "BearingFactor" << std::endl;
|
std::cout << s << "BearingFactor" << std::endl;
|
||||||
Base::print(s, kf);
|
Base::print(s, kf);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
private:
|
||||||
|
friend class boost::serialization::access;
|
||||||
|
template <class ARCHIVE>
|
||||||
|
void serialize(ARCHIVE& ar, const unsigned int /*version*/) {
|
||||||
|
ar& boost::serialization::make_nvp(
|
||||||
|
"Base", boost::serialization::base_object<Base>(*this));
|
||||||
|
}
|
||||||
}; // BearingFactor
|
}; // BearingFactor
|
||||||
|
|
||||||
/// traits
|
/// traits
|
||||||
|
|
|
@ -73,6 +73,14 @@ class BearingRangeFactor
|
||||||
Base::print(s, kf);
|
Base::print(s, kf);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
private:
|
||||||
|
friend class boost::serialization::access;
|
||||||
|
template <class ARCHIVE>
|
||||||
|
void serialize(ARCHIVE& ar, const unsigned int /*version*/) {
|
||||||
|
ar& boost::serialization::make_nvp(
|
||||||
|
"Base", boost::serialization::base_object<Base>(*this));
|
||||||
|
}
|
||||||
}; // BearingRangeFactor
|
}; // BearingRangeFactor
|
||||||
|
|
||||||
/// traits
|
/// traits
|
||||||
|
|
|
@ -65,6 +65,14 @@ class RangeFactor : public ExpressionFactor2<T, A1, A2> {
|
||||||
std::cout << s << "RangeFactor" << std::endl;
|
std::cout << s << "RangeFactor" << std::endl;
|
||||||
Base::print(s, kf);
|
Base::print(s, kf);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
private:
|
||||||
|
friend class boost::serialization::access;
|
||||||
|
template <class ARCHIVE>
|
||||||
|
void serialize(ARCHIVE& ar, const unsigned int /*version*/) {
|
||||||
|
ar& boost::serialization::make_nvp(
|
||||||
|
"Base", boost::serialization::base_object<Base>(*this));
|
||||||
|
}
|
||||||
}; // \ RangeFactor
|
}; // \ RangeFactor
|
||||||
|
|
||||||
/// traits
|
/// traits
|
||||||
|
|
|
@ -54,7 +54,8 @@ S13 = [
|
||||||
+0.00,-8.94427
|
+0.00,-8.94427
|
||||||
];
|
];
|
||||||
d=[2.23607;-1.56525];
|
d=[2.23607;-1.56525];
|
||||||
expectedCG = GaussianConditional(x2,d,R11,l1,S12,x1,S13);
|
unit2 = noiseModel.Unit.Create(2);
|
||||||
|
expectedCG = GaussianConditional(x2,d,R11,l1,S12,x1,S13,unit2);
|
||||||
% check if the result matches
|
% check if the result matches
|
||||||
CHECK('actualCG.equals(expectedCG,1e-5)',actualCG.equals(expectedCG,1e-4));
|
CHECK('actualCG.equals(expectedCG,1e-5)',actualCG.equals(expectedCG,1e-4));
|
||||||
|
|
||||||
|
|
|
@ -52,14 +52,26 @@ priorMean = Pose2(0.0, 0.0, 0.0); % prior at origin
|
||||||
priorNoise = noiseModel.Diagonal.Sigmas([0.3; 0.3; 0.1]);
|
priorNoise = noiseModel.Diagonal.Sigmas([0.3; 0.3; 0.1]);
|
||||||
graph.add(PriorFactorPose2(i1, priorMean, priorNoise)); % add directly to graph
|
graph.add(PriorFactorPose2(i1, priorMean, priorNoise)); % add directly to graph
|
||||||
|
|
||||||
% Between Factors - FAIL: unregistered class
|
% Between Factors
|
||||||
odometry = Pose2(2.0, 0.0, 0.0);
|
odometry = Pose2(2.0, 0.0, 0.0);
|
||||||
odometryNoise = noiseModel.Diagonal.Sigmas([0.2; 0.2; 0.1]);
|
odometryNoise = noiseModel.Diagonal.Sigmas([0.2; 0.2; 0.1]);
|
||||||
graph.add(BetweenFactorPose2(i1, i2, odometry, odometryNoise));
|
graph.add(BetweenFactorPose2(i1, i2, odometry, odometryNoise));
|
||||||
graph.add(BetweenFactorPose2(i2, i3, odometry, odometryNoise));
|
graph.add(BetweenFactorPose2(i2, i3, odometry, odometryNoise));
|
||||||
|
|
||||||
% BearingRange Factors - FAIL: unregistered class
|
% Range Factors
|
||||||
|
rNoise = noiseModel.Diagonal.Sigmas([0.2]);
|
||||||
|
graph.add(RangeFactorPosePoint2(i1, j1, sqrt(4+4), rNoise));
|
||||||
|
graph.add(RangeFactorPosePoint2(i2, j1, 2, rNoise));
|
||||||
|
graph.add(RangeFactorPosePoint2(i3, j2, 2, rNoise));
|
||||||
|
|
||||||
|
% Bearing Factors
|
||||||
degrees = pi/180;
|
degrees = pi/180;
|
||||||
|
bNoise = noiseModel.Diagonal.Sigmas([0.1]);
|
||||||
|
graph.add(BearingFactor2D(i1, j1, Rot2(45*degrees), bNoise));
|
||||||
|
graph.add(BearingFactor2D(i2, j1, Rot2(90*degrees), bNoise));
|
||||||
|
graph.add(BearingFactor2D(i3, j2, Rot2(90*degrees), bNoise));
|
||||||
|
|
||||||
|
% BearingRange Factors
|
||||||
brNoise = noiseModel.Diagonal.Sigmas([0.1; 0.2]);
|
brNoise = noiseModel.Diagonal.Sigmas([0.1; 0.2]);
|
||||||
graph.add(BearingRangeFactor2D(i1, j1, Rot2(45*degrees), sqrt(4+4), brNoise));
|
graph.add(BearingRangeFactor2D(i1, j1, Rot2(45*degrees), sqrt(4+4), brNoise));
|
||||||
graph.add(BearingRangeFactor2D(i2, j1, Rot2(90*degrees), 2, brNoise));
|
graph.add(BearingRangeFactor2D(i2, j1, Rot2(90*degrees), 2, brNoise));
|
||||||
|
|
|
@ -273,9 +273,9 @@ void Module::generate_matlab_wrapper(const string& toolboxPath) const {
|
||||||
|
|
||||||
// Include boost.serialization archive headers before other class headers
|
// Include boost.serialization archive headers before other class headers
|
||||||
if (hasSerialiable) {
|
if (hasSerialiable) {
|
||||||
wrapperFile.oss << "#include <boost/serialization/export.hpp>\n";
|
|
||||||
wrapperFile.oss << "#include <boost/archive/text_iarchive.hpp>\n";
|
wrapperFile.oss << "#include <boost/archive/text_iarchive.hpp>\n";
|
||||||
wrapperFile.oss << "#include <boost/archive/text_oarchive.hpp>\n\n";
|
wrapperFile.oss << "#include <boost/archive/text_oarchive.hpp>\n";
|
||||||
|
wrapperFile.oss << "#include <boost/serialization/export.hpp>\n\n";
|
||||||
}
|
}
|
||||||
|
|
||||||
// Generate includes while avoiding redundant includes
|
// Generate includes while avoiding redundant includes
|
||||||
|
|
|
@ -1,9 +1,9 @@
|
||||||
#include <wrap/matlab.h>
|
#include <wrap/matlab.h>
|
||||||
#include <map>
|
#include <map>
|
||||||
|
|
||||||
#include <boost/serialization/export.hpp>
|
|
||||||
#include <boost/archive/text_iarchive.hpp>
|
#include <boost/archive/text_iarchive.hpp>
|
||||||
#include <boost/archive/text_oarchive.hpp>
|
#include <boost/archive/text_oarchive.hpp>
|
||||||
|
#include <boost/serialization/export.hpp>
|
||||||
|
|
||||||
#include <folder/path/to/Test.h>
|
#include <folder/path/to/Test.h>
|
||||||
#include <gtsam/geometry/Point2.h>
|
#include <gtsam/geometry/Point2.h>
|
||||||
|
|
Loading…
Reference in New Issue