fixed smart factors serialization, add unit tests]
parent
31eec5317c
commit
6ab909a92c
|
|
@ -376,6 +376,15 @@ class TriangulationResult: public boost::optional<Point3> {
|
||||||
status_(s) {
|
status_(s) {
|
||||||
}
|
}
|
||||||
public:
|
public:
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Default constructor, only for serialization
|
||||||
|
*/
|
||||||
|
TriangulationResult() {}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Constructor
|
||||||
|
*/
|
||||||
TriangulationResult(const Point3& p) :
|
TriangulationResult(const Point3& p) :
|
||||||
status_(VALID) {
|
status_(VALID) {
|
||||||
reset(p);
|
reset(p);
|
||||||
|
|
|
||||||
|
|
@ -93,6 +93,9 @@ public:
|
||||||
/// We use the new CameraSte data structure to refer to a set of cameras
|
/// We use the new CameraSte data structure to refer to a set of cameras
|
||||||
typedef CameraSet<CAMERA> Cameras;
|
typedef CameraSet<CAMERA> Cameras;
|
||||||
|
|
||||||
|
/// Default Constructor, for serialization
|
||||||
|
SmartFactorBase() {}
|
||||||
|
|
||||||
/// Constructor
|
/// Constructor
|
||||||
SmartFactorBase(const SharedNoiseModel& sharedNoiseModel,
|
SmartFactorBase(const SharedNoiseModel& sharedNoiseModel,
|
||||||
boost::optional<Pose3> body_P_sensor = boost::none) :
|
boost::optional<Pose3> body_P_sensor = boost::none) :
|
||||||
|
|
|
||||||
|
|
@ -137,7 +137,7 @@ protected:
|
||||||
|
|
||||||
/// @name Parameters
|
/// @name Parameters
|
||||||
/// @{
|
/// @{
|
||||||
const SmartProjectionParams params_;
|
SmartProjectionParams params_;
|
||||||
/// @}
|
/// @}
|
||||||
|
|
||||||
/// @name Caching triangulation
|
/// @name Caching triangulation
|
||||||
|
|
@ -154,6 +154,11 @@ public:
|
||||||
/// shorthand for a set of cameras
|
/// shorthand for a set of cameras
|
||||||
typedef CameraSet<CAMERA> Cameras;
|
typedef CameraSet<CAMERA> Cameras;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Default constructor, only for serialization
|
||||||
|
*/
|
||||||
|
SmartProjectionFactor() {}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Constructor
|
* Constructor
|
||||||
* @param body_P_sensor pose of the camera in the body frame
|
* @param body_P_sensor pose of the camera in the body frame
|
||||||
|
|
|
||||||
|
|
@ -59,6 +59,11 @@ public:
|
||||||
/// shorthand for a smart pointer to a factor
|
/// shorthand for a smart pointer to a factor
|
||||||
typedef boost::shared_ptr<This> shared_ptr;
|
typedef boost::shared_ptr<This> shared_ptr;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Default constructor, only for serialization
|
||||||
|
*/
|
||||||
|
SmartProjectionPoseFactor() {}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Constructor
|
* Constructor
|
||||||
* @param Isotropic measurement noise
|
* @param Isotropic measurement noise
|
||||||
|
|
|
||||||
|
|
@ -18,6 +18,7 @@
|
||||||
|
|
||||||
#include <gtsam/slam/SmartFactorBase.h>
|
#include <gtsam/slam/SmartFactorBase.h>
|
||||||
#include <gtsam/geometry/Pose3.h>
|
#include <gtsam/geometry/Pose3.h>
|
||||||
|
#include <gtsam/base/serializationTestHelpers.h>
|
||||||
#include <CppUnitLite/TestHarness.h>
|
#include <CppUnitLite/TestHarness.h>
|
||||||
|
|
||||||
using namespace std;
|
using namespace std;
|
||||||
|
|
@ -29,9 +30,13 @@ static SharedNoiseModel unit3(noiseModel::Unit::Create(3));
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
#include <gtsam/geometry/PinholeCamera.h>
|
#include <gtsam/geometry/PinholeCamera.h>
|
||||||
#include <gtsam/geometry/Cal3Bundler.h>
|
#include <gtsam/geometry/Cal3Bundler.h>
|
||||||
|
|
||||||
|
namespace gtsam {
|
||||||
|
|
||||||
class PinholeFactor: public SmartFactorBase<PinholeCamera<Cal3Bundler> > {
|
class PinholeFactor: public SmartFactorBase<PinholeCamera<Cal3Bundler> > {
|
||||||
public:
|
public:
|
||||||
typedef SmartFactorBase<PinholeCamera<Cal3Bundler> > Base;
|
typedef SmartFactorBase<PinholeCamera<Cal3Bundler> > Base;
|
||||||
|
PinholeFactor() {}
|
||||||
PinholeFactor(const SharedNoiseModel& sharedNoiseModel): Base(sharedNoiseModel) {
|
PinholeFactor(const SharedNoiseModel& sharedNoiseModel): Base(sharedNoiseModel) {
|
||||||
}
|
}
|
||||||
virtual double error(const Values& values) const {
|
virtual double error(const Values& values) const {
|
||||||
|
|
@ -43,6 +48,11 @@ public:
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
|
/// traits
|
||||||
|
template<>
|
||||||
|
struct traits<PinholeFactor> : public Testable<PinholeFactor> {};
|
||||||
|
}
|
||||||
|
|
||||||
TEST(SmartFactorBase, Pinhole) {
|
TEST(SmartFactorBase, Pinhole) {
|
||||||
PinholeFactor f= PinholeFactor(unit2);
|
PinholeFactor f= PinholeFactor(unit2);
|
||||||
f.add(Point2(), 1);
|
f.add(Point2(), 1);
|
||||||
|
|
@ -52,9 +62,13 @@ TEST(SmartFactorBase, Pinhole) {
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
#include <gtsam/geometry/StereoCamera.h>
|
#include <gtsam/geometry/StereoCamera.h>
|
||||||
|
|
||||||
|
namespace gtsam {
|
||||||
|
|
||||||
class StereoFactor: public SmartFactorBase<StereoCamera> {
|
class StereoFactor: public SmartFactorBase<StereoCamera> {
|
||||||
public:
|
public:
|
||||||
typedef SmartFactorBase<StereoCamera> Base;
|
typedef SmartFactorBase<StereoCamera> Base;
|
||||||
|
StereoFactor() {}
|
||||||
StereoFactor(const SharedNoiseModel& sharedNoiseModel): Base(sharedNoiseModel) {
|
StereoFactor(const SharedNoiseModel& sharedNoiseModel): Base(sharedNoiseModel) {
|
||||||
}
|
}
|
||||||
virtual double error(const Values& values) const {
|
virtual double error(const Values& values) const {
|
||||||
|
|
@ -66,6 +80,11 @@ public:
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
|
/// traits
|
||||||
|
template<>
|
||||||
|
struct traits<StereoFactor> : public Testable<StereoFactor> {};
|
||||||
|
}
|
||||||
|
|
||||||
TEST(SmartFactorBase, Stereo) {
|
TEST(SmartFactorBase, Stereo) {
|
||||||
StereoFactor f(unit3);
|
StereoFactor f(unit3);
|
||||||
f.add(StereoPoint2(), 1);
|
f.add(StereoPoint2(), 1);
|
||||||
|
|
@ -73,6 +92,24 @@ TEST(SmartFactorBase, Stereo) {
|
||||||
EXPECT_LONGS_EQUAL(2 * 3, f.dim());
|
EXPECT_LONGS_EQUAL(2 * 3, f.dim());
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/* ************************************************************************* */
|
||||||
|
BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Constrained, "gtsam_noiseModel_Constrained");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Diagonal, "gtsam_noiseModel_Diagonal");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Gaussian, "gtsam_noiseModel_Gaussian");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Unit, "gtsam_noiseModel_Unit");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Isotropic, "gtsam_noiseModel_Isotropic");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(gtsam::SharedNoiseModel, "gtsam_SharedNoiseModel");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(gtsam::SharedDiagonal, "gtsam_SharedDiagonal");
|
||||||
|
|
||||||
|
TEST(SmartFactorBase, serialize) {
|
||||||
|
using namespace gtsam::serializationTestHelpers;
|
||||||
|
PinholeFactor factor(unit2);
|
||||||
|
|
||||||
|
EXPECT(equalsObj(factor));
|
||||||
|
EXPECT(equalsXML(factor));
|
||||||
|
EXPECT(equalsBinary(factor));
|
||||||
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
int main() {
|
int main() {
|
||||||
TestResult tr;
|
TestResult tr;
|
||||||
|
|
|
||||||
|
|
@ -22,6 +22,7 @@
|
||||||
#include "smartFactorScenarios.h"
|
#include "smartFactorScenarios.h"
|
||||||
#include <gtsam/slam/SmartProjectionFactor.h>
|
#include <gtsam/slam/SmartProjectionFactor.h>
|
||||||
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
|
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
|
||||||
|
#include <gtsam/base/serializationTestHelpers.h>
|
||||||
#include <CppUnitLite/TestHarness.h>
|
#include <CppUnitLite/TestHarness.h>
|
||||||
#include <boost/assign/std/map.hpp>
|
#include <boost/assign/std/map.hpp>
|
||||||
#include <iostream>
|
#include <iostream>
|
||||||
|
|
@ -843,6 +844,26 @@ TEST( SmartProjectionCameraFactor, implicitJacobianFactor ) {
|
||||||
EXPECT(assert_equal(yActual, yExpected, 1e-7));
|
EXPECT(assert_equal(yActual, yExpected, 1e-7));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/* ************************************************************************* */
|
||||||
|
BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Constrained, "gtsam_noiseModel_Constrained");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Diagonal, "gtsam_noiseModel_Diagonal");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Gaussian, "gtsam_noiseModel_Gaussian");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Unit, "gtsam_noiseModel_Unit");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Isotropic, "gtsam_noiseModel_Isotropic");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(gtsam::SharedNoiseModel, "gtsam_SharedNoiseModel");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(gtsam::SharedDiagonal, "gtsam_SharedDiagonal");
|
||||||
|
|
||||||
|
TEST( SmartProjectionCameraFactor, serialize) {
|
||||||
|
using namespace vanilla;
|
||||||
|
using namespace gtsam::serializationTestHelpers;
|
||||||
|
SmartFactor factor(unit2);
|
||||||
|
|
||||||
|
EXPECT(equalsObj(factor));
|
||||||
|
EXPECT(equalsXML(factor));
|
||||||
|
EXPECT(equalsBinary(factor));
|
||||||
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
int main() {
|
int main() {
|
||||||
TestResult tr;
|
TestResult tr;
|
||||||
|
|
|
||||||
|
|
@ -24,6 +24,7 @@
|
||||||
#include <gtsam/slam/PoseTranslationPrior.h>
|
#include <gtsam/slam/PoseTranslationPrior.h>
|
||||||
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
|
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
|
||||||
#include <gtsam/base/numericalDerivative.h>
|
#include <gtsam/base/numericalDerivative.h>
|
||||||
|
#include <gtsam/base/serializationTestHelpers.h>
|
||||||
#include <CppUnitLite/TestHarness.h>
|
#include <CppUnitLite/TestHarness.h>
|
||||||
#include <boost/assign/std/map.hpp>
|
#include <boost/assign/std/map.hpp>
|
||||||
#include <iostream>
|
#include <iostream>
|
||||||
|
|
@ -1387,6 +1388,27 @@ TEST( SmartProjectionPoseFactor, Cal3BundlerRotationOnly ) {
|
||||||
values.at<Pose3>(x3)));
|
values.at<Pose3>(x3)));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/* ************************************************************************* */
|
||||||
|
BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Constrained, "gtsam_noiseModel_Constrained");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Diagonal, "gtsam_noiseModel_Diagonal");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Gaussian, "gtsam_noiseModel_Gaussian");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Unit, "gtsam_noiseModel_Unit");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Isotropic, "gtsam_noiseModel_Isotropic");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(gtsam::SharedNoiseModel, "gtsam_SharedNoiseModel");
|
||||||
|
BOOST_CLASS_EXPORT_GUID(gtsam::SharedDiagonal, "gtsam_SharedDiagonal");
|
||||||
|
|
||||||
|
TEST(SmartProjectionPoseFactor, serialize) {
|
||||||
|
using namespace vanillaPose;
|
||||||
|
using namespace gtsam::serializationTestHelpers;
|
||||||
|
SmartProjectionParams params;
|
||||||
|
params.setRankTolerance(rankTol);
|
||||||
|
SmartFactor factor(model, sharedK, boost::none, params);
|
||||||
|
|
||||||
|
EXPECT(equalsObj(factor));
|
||||||
|
EXPECT(equalsXML(factor));
|
||||||
|
EXPECT(equalsBinary(factor));
|
||||||
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
int main() {
|
int main() {
|
||||||
TestResult tr;
|
TestResult tr;
|
||||||
|
|
|
||||||
Loading…
Reference in New Issue