Better serialization tests
parent
bf88906c3f
commit
bc1c5d7bad
|
|
@ -49,9 +49,9 @@ BOOST_CLASS_EXPORT(gtsam::noiseModel::Isotropic);
|
|||
|
||||
/* ************************************************************************* */
|
||||
TEST(BearingFactor, Serialization2D) {
|
||||
EXPECT(serializationTestHelpers::equalsObj<BearingFactor2D>(factor2D));
|
||||
EXPECT(serializationTestHelpers::equalsXML<BearingFactor2D>(factor2D));
|
||||
EXPECT(serializationTestHelpers::equalsBinary<BearingFactor2D>(factor2D));
|
||||
EXPECT(serializationTestHelpers::equalsObj(factor2D));
|
||||
EXPECT(serializationTestHelpers::equalsXML(factor2D));
|
||||
EXPECT(serializationTestHelpers::equalsBinary(factor2D));
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
|
|
@ -75,9 +75,9 @@ TEST(BearingFactor, 2D) {
|
|||
|
||||
/* ************************************************************************* */
|
||||
TEST(BearingFactor, Serialization3D) {
|
||||
EXPECT(serializationTestHelpers::equalsObj<BearingFactor3D>(factor3D));
|
||||
EXPECT(serializationTestHelpers::equalsXML<BearingFactor3D>(factor3D));
|
||||
EXPECT(serializationTestHelpers::equalsBinary<BearingFactor3D>(factor3D));
|
||||
EXPECT(serializationTestHelpers::equalsObj(factor3D));
|
||||
EXPECT(serializationTestHelpers::equalsXML(factor3D));
|
||||
EXPECT(serializationTestHelpers::equalsBinary(factor3D));
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
|
|
|
|||
|
|
@ -28,7 +28,6 @@
|
|||
|
||||
using namespace std;
|
||||
using namespace gtsam;
|
||||
using namespace serializationTestHelpers;
|
||||
|
||||
Key poseKey(1);
|
||||
Key pointKey(2);
|
||||
|
|
@ -49,9 +48,9 @@ BOOST_CLASS_EXPORT(gtsam::noiseModel::Isotropic);
|
|||
|
||||
/* ************************************************************************* */
|
||||
TEST(BearingRangeFactor, Serialization2D) {
|
||||
EXPECT(equalsObj<BearingRangeFactor2D>(factor2D));
|
||||
EXPECT(equalsXML<BearingRangeFactor2D>(factor2D));
|
||||
EXPECT(equalsBinary<BearingRangeFactor2D>(factor2D));
|
||||
EXPECT(serializationTestHelpers::equalsObj(factor2D));
|
||||
EXPECT(serializationTestHelpers::equalsXML(factor2D));
|
||||
EXPECT(serializationTestHelpers::equalsBinary(factor2D));
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
|
|
@ -75,9 +74,9 @@ TEST(BearingRangeFactor, 2D) {
|
|||
|
||||
/* ************************************************************************* */
|
||||
TEST(BearingRangeFactor, Serialization3D) {
|
||||
EXPECT(equalsObj<BearingRangeFactor3D>(factor3D));
|
||||
EXPECT(equalsXML<BearingRangeFactor3D>(factor3D));
|
||||
EXPECT(equalsBinary<BearingRangeFactor3D>(factor3D));
|
||||
EXPECT(serializationTestHelpers::equalsObj(factor3D));
|
||||
EXPECT(serializationTestHelpers::equalsXML(factor3D));
|
||||
EXPECT(serializationTestHelpers::equalsBinary(factor3D));
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
|
|
|
|||
|
|
@ -18,10 +18,9 @@
|
|||
|
||||
#include <gtsam/sam/RangeFactor.h>
|
||||
#include <gtsam/geometry/Pose3.h>
|
||||
#include <gtsam/geometry/Point3.h>
|
||||
#include <gtsam/geometry/Pose2.h>
|
||||
#include <gtsam/geometry/Point2.h>
|
||||
#include <gtsam/base/numericalDerivative.h>
|
||||
#include <gtsam/base/serializationTestHelpers.h>
|
||||
#include <gtsam/base/TestableAssertions.h>
|
||||
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
|
|
@ -38,6 +37,10 @@ typedef RangeFactor<Pose3, Point3> RangeFactor3D;
|
|||
typedef RangeFactorWithTransform<Pose2, Point2> RangeFactorWithTransform2D;
|
||||
typedef RangeFactorWithTransform<Pose3, Point3> RangeFactorWithTransform3D;
|
||||
|
||||
Key poseKey(1);
|
||||
Key pointKey(2);
|
||||
double measurement(10.0);
|
||||
|
||||
/* ************************************************************************* */
|
||||
Vector factorError2D(const Pose2& pose, const Point2& point,
|
||||
const RangeFactor2D& factor) {
|
||||
|
|
@ -64,19 +67,33 @@ Vector factorErrorWithTransform3D(const Pose3& pose, const Point3& point,
|
|||
|
||||
/* ************************************************************************* */
|
||||
TEST( RangeFactor, Constructor) {
|
||||
Key poseKey(1);
|
||||
Key pointKey(2);
|
||||
double measurement(10.0);
|
||||
|
||||
RangeFactor2D factor2D(poseKey, pointKey, measurement, model);
|
||||
RangeFactor3D factor3D(poseKey, pointKey, measurement, model);
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
// Export Noisemodels
|
||||
// See http://www.boost.org/doc/libs/1_32_0/libs/serialization/doc/special.html
|
||||
BOOST_CLASS_EXPORT(gtsam::noiseModel::Unit);
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST(RangeFactor, Serialization2D) {
|
||||
RangeFactor2D factor2D(poseKey, pointKey, measurement, model);
|
||||
EXPECT(serializationTestHelpers::equalsObj(factor2D));
|
||||
EXPECT(serializationTestHelpers::equalsXML(factor2D));
|
||||
EXPECT(serializationTestHelpers::equalsBinary(factor2D));
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST(RangeFactor, Serialization3D) {
|
||||
RangeFactor3D factor3D(poseKey, pointKey, measurement, model);
|
||||
EXPECT(serializationTestHelpers::equalsObj(factor3D));
|
||||
EXPECT(serializationTestHelpers::equalsXML(factor3D));
|
||||
EXPECT(serializationTestHelpers::equalsBinary(factor3D));
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST( RangeFactor, ConstructorWithTransform) {
|
||||
Key poseKey(1);
|
||||
Key pointKey(2);
|
||||
double measurement(10.0);
|
||||
Pose2 body_P_sensor_2D(0.25, -0.10, -M_PI_2);
|
||||
Pose3 body_P_sensor_3D(Rot3::RzRyRx(-M_PI_2, 0.0, -M_PI_2),
|
||||
Point3(0.25, -0.10, 1.0));
|
||||
|
|
@ -90,10 +107,6 @@ TEST( RangeFactor, ConstructorWithTransform) {
|
|||
/* ************************************************************************* */
|
||||
TEST( RangeFactor, Equals ) {
|
||||
// Create two identical factors and make sure they're equal
|
||||
Key poseKey(1);
|
||||
Key pointKey(2);
|
||||
double measurement(10.0);
|
||||
|
||||
RangeFactor2D factor2D_1(poseKey, pointKey, measurement, model);
|
||||
RangeFactor2D factor2D_2(poseKey, pointKey, measurement, model);
|
||||
CHECK(assert_equal(factor2D_1, factor2D_2));
|
||||
|
|
@ -106,9 +119,6 @@ TEST( RangeFactor, Equals ) {
|
|||
/* ************************************************************************* */
|
||||
TEST( RangeFactor, EqualsWithTransform ) {
|
||||
// Create two identical factors and make sure they're equal
|
||||
Key poseKey(1);
|
||||
Key pointKey(2);
|
||||
double measurement(10.0);
|
||||
Pose2 body_P_sensor_2D(0.25, -0.10, -M_PI_2);
|
||||
Pose3 body_P_sensor_3D(Rot3::RzRyRx(-M_PI_2, 0.0, -M_PI_2),
|
||||
Point3(0.25, -0.10, 1.0));
|
||||
|
|
@ -129,9 +139,6 @@ TEST( RangeFactor, EqualsWithTransform ) {
|
|||
/* ************************************************************************* */
|
||||
TEST( RangeFactor, Error2D ) {
|
||||
// Create a factor
|
||||
Key poseKey(1);
|
||||
Key pointKey(2);
|
||||
double measurement(10.0);
|
||||
RangeFactor2D factor(poseKey, pointKey, measurement, model);
|
||||
|
||||
// Set the linearization point
|
||||
|
|
@ -151,9 +158,6 @@ TEST( RangeFactor, Error2D ) {
|
|||
/* ************************************************************************* */
|
||||
TEST( RangeFactor, Error2DWithTransform ) {
|
||||
// Create a factor
|
||||
Key poseKey(1);
|
||||
Key pointKey(2);
|
||||
double measurement(10.0);
|
||||
Pose2 body_P_sensor(0.25, -0.10, -M_PI_2);
|
||||
RangeFactorWithTransform2D factor(poseKey, pointKey, measurement, model,
|
||||
body_P_sensor);
|
||||
|
|
@ -177,9 +181,6 @@ TEST( RangeFactor, Error2DWithTransform ) {
|
|||
/* ************************************************************************* */
|
||||
TEST( RangeFactor, Error3D ) {
|
||||
// Create a factor
|
||||
Key poseKey(1);
|
||||
Key pointKey(2);
|
||||
double measurement(10.0);
|
||||
RangeFactor3D factor(poseKey, pointKey, measurement, model);
|
||||
|
||||
// Set the linearization point
|
||||
|
|
@ -199,9 +200,6 @@ TEST( RangeFactor, Error3D ) {
|
|||
/* ************************************************************************* */
|
||||
TEST( RangeFactor, Error3DWithTransform ) {
|
||||
// Create a factor
|
||||
Key poseKey(1);
|
||||
Key pointKey(2);
|
||||
double measurement(10.0);
|
||||
Pose3 body_P_sensor(Rot3::RzRyRx(-M_PI_2, 0.0, -M_PI_2),
|
||||
Point3(0.25, -0.10, 1.0));
|
||||
RangeFactorWithTransform3D factor(poseKey, pointKey, measurement, model,
|
||||
|
|
@ -226,9 +224,6 @@ TEST( RangeFactor, Error3DWithTransform ) {
|
|||
/* ************************************************************************* */
|
||||
TEST( RangeFactor, Jacobian2D ) {
|
||||
// Create a factor
|
||||
Key poseKey(1);
|
||||
Key pointKey(2);
|
||||
double measurement(10.0);
|
||||
RangeFactor2D factor(poseKey, pointKey, measurement, model);
|
||||
|
||||
// Set the linearization point
|
||||
|
|
@ -254,9 +249,6 @@ TEST( RangeFactor, Jacobian2D ) {
|
|||
/* ************************************************************************* */
|
||||
TEST( RangeFactor, Jacobian2DWithTransform ) {
|
||||
// Create a factor
|
||||
Key poseKey(1);
|
||||
Key pointKey(2);
|
||||
double measurement(10.0);
|
||||
Pose2 body_P_sensor(0.25, -0.10, -M_PI_2);
|
||||
RangeFactorWithTransform2D factor(poseKey, pointKey, measurement, model,
|
||||
body_P_sensor);
|
||||
|
|
@ -286,9 +278,6 @@ TEST( RangeFactor, Jacobian2DWithTransform ) {
|
|||
/* ************************************************************************* */
|
||||
TEST( RangeFactor, Jacobian3D ) {
|
||||
// Create a factor
|
||||
Key poseKey(1);
|
||||
Key pointKey(2);
|
||||
double measurement(10.0);
|
||||
RangeFactor3D factor(poseKey, pointKey, measurement, model);
|
||||
|
||||
// Set the linearization point
|
||||
|
|
@ -314,9 +303,6 @@ TEST( RangeFactor, Jacobian3D ) {
|
|||
/* ************************************************************************* */
|
||||
TEST( RangeFactor, Jacobian3DWithTransform ) {
|
||||
// Create a factor
|
||||
Key poseKey(1);
|
||||
Key pointKey(2);
|
||||
double measurement(10.0);
|
||||
Pose3 body_P_sensor(Rot3::RzRyRx(-M_PI_2, 0.0, -M_PI_2),
|
||||
Point3(0.25, -0.10, 1.0));
|
||||
RangeFactorWithTransform3D factor(poseKey, pointKey, measurement, model,
|
||||
|
|
@ -348,9 +334,6 @@ TEST( RangeFactor, Jacobian3DWithTransform ) {
|
|||
// Do a test with Point3
|
||||
TEST(RangeFactor, Point3) {
|
||||
// Create a factor
|
||||
Key poseKey(1);
|
||||
Key pointKey(2);
|
||||
double measurement(10.0);
|
||||
RangeFactor<Point3> factor(poseKey, pointKey, measurement, model);
|
||||
|
||||
// Set the linearization point
|
||||
|
|
|
|||
Loading…
Reference in New Issue