From cdc121cf7da30408aed14a05f24924ad98c07a7e Mon Sep 17 00:00:00 2001 From: Jing Dong Date: Fri, 17 Oct 2014 14:25:42 -0400 Subject: [PATCH] add in testSerialization --- gtsam/geometry/Cal3Unified.h | 2 +- gtsam/geometry/tests/testSerializationGeometry.cpp | 3 +++ 2 files changed, 4 insertions(+), 1 deletion(-) diff --git a/gtsam/geometry/Cal3Unified.h b/gtsam/geometry/Cal3Unified.h index 750d2ed73..03db6af9a 100644 --- a/gtsam/geometry/Cal3Unified.h +++ b/gtsam/geometry/Cal3Unified.h @@ -90,7 +90,7 @@ public: /** * convert intrinsic coordinates xy to image coordinates uv * @param p point in intrinsic coordinates - * @param Dcal optional 2*9 Jacobian wrpt Cal3DS2 parameters + * @param Dcal optional 2*10 Jacobian wrpt Cal3Unified parameters * @param Dp optional 2*2 Jacobian wrpt intrinsic coordinates * @return point in image coordinates */ diff --git a/gtsam/geometry/tests/testSerializationGeometry.cpp b/gtsam/geometry/tests/testSerializationGeometry.cpp index 95001a033..a7e792cb8 100644 --- a/gtsam/geometry/tests/testSerializationGeometry.cpp +++ b/gtsam/geometry/tests/testSerializationGeometry.cpp @@ -25,6 +25,7 @@ #include #include #include +#include #include #include @@ -46,6 +47,7 @@ static Cal3Bundler cal3(1.0, 2.0, 3.0); static Cal3_S2Stereo cal4(1.0, 2.0, 3.0, 4.0, 5.0, 6.0); static Cal3_S2Stereo::shared_ptr cal4ptr(new Cal3_S2Stereo(cal4)); static CalibratedCamera cal5(Pose3(rt3, pt3)); +static Cal3Unified cal6(1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0, 8.0, 9.0, 10.0); static PinholeCamera cam1(pose3, cal1); static StereoCamera cam2(pose3, cal4ptr); @@ -66,6 +68,7 @@ TEST (Serialization, text_geometry) { EXPECT(equalsObj(cal3)); EXPECT(equalsObj(cal4)); EXPECT(equalsObj(cal5)); + EXPECT(equalsObj(cal6)); EXPECT(equalsObj(cam1)); EXPECT(equalsObj(cam2));