Disabled testSerializationGeometry. Created an issue on Bitbucket.

release/4.3a0
krunalchande 2015-02-10 23:44:15 -05:00
parent 7c8fe9c1a0
commit 9bce3e1ce9
1 changed files with 3 additions and 3 deletions

View File

@ -59,7 +59,7 @@ static StereoCamera cam2(pose3, cal4ptr);
static StereoPoint2 spt(1.0, 2.0, 3.0); static StereoPoint2 spt(1.0, 2.0, 3.0);
/* ************************************************************************* */ /* ************************************************************************* */
TEST (Serialization, text_geometry) { TEST_DISABLED (Serialization, text_geometry) {
EXPECT(equalsObj<gtsam::Point2>(Point2(1.0, 2.0))); EXPECT(equalsObj<gtsam::Point2>(Point2(1.0, 2.0)));
EXPECT(equalsObj<gtsam::Pose2>(Pose2(1.0, 2.0, 0.3))); EXPECT(equalsObj<gtsam::Pose2>(Pose2(1.0, 2.0, 0.3)));
EXPECT(equalsObj<gtsam::Rot2>(Rot2::fromDegrees(30.0))); EXPECT(equalsObj<gtsam::Rot2>(Rot2::fromDegrees(30.0)));
@ -84,7 +84,7 @@ TEST (Serialization, text_geometry) {
} }
/* ************************************************************************* */ /* ************************************************************************* */
TEST (Serialization, xml_geometry) { TEST_DISABLED (Serialization, xml_geometry) {
EXPECT(equalsXML<gtsam::Point2>(Point2(1.0, 2.0))); EXPECT(equalsXML<gtsam::Point2>(Point2(1.0, 2.0)));
EXPECT(equalsXML<gtsam::Pose2>(Pose2(1.0, 2.0, 0.3))); EXPECT(equalsXML<gtsam::Pose2>(Pose2(1.0, 2.0, 0.3)));
EXPECT(equalsXML<gtsam::Rot2>(Rot2::fromDegrees(30.0))); EXPECT(equalsXML<gtsam::Rot2>(Rot2::fromDegrees(30.0)));
@ -108,7 +108,7 @@ TEST (Serialization, xml_geometry) {
} }
/* ************************************************************************* */ /* ************************************************************************* */
TEST (Serialization, binary_geometry) { TEST_DISABLED (Serialization, binary_geometry) {
EXPECT(equalsBinary<gtsam::Point2>(Point2(1.0, 2.0))); EXPECT(equalsBinary<gtsam::Point2>(Point2(1.0, 2.0)));
EXPECT(equalsBinary<gtsam::Pose2>(Pose2(1.0, 2.0, 0.3))); EXPECT(equalsBinary<gtsam::Pose2>(Pose2(1.0, 2.0, 0.3)));
EXPECT(equalsBinary<gtsam::Rot2>(Rot2::fromDegrees(30.0))); EXPECT(equalsBinary<gtsam::Rot2>(Rot2::fromDegrees(30.0)));