From 8fdbf2fa6e25f3fde36947e710a7221fe74f4434 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sat, 21 Mar 2020 15:29:07 -0400 Subject: [PATCH] added Cal3_S2 header and Frank's recommendations --- examples/CameraResectioning.cpp | 1 + examples/ISAM2Example_SmartFactor.cpp | 1 + examples/ImuFactorExample2.cpp | 3 ++- gtsam/sam/tests/testRangeFactor.cpp | 8 +++++--- 4 files changed, 9 insertions(+), 4 deletions(-) diff --git a/examples/CameraResectioning.cpp b/examples/CameraResectioning.cpp index e93e6ffca..b12418098 100644 --- a/examples/CameraResectioning.cpp +++ b/examples/CameraResectioning.cpp @@ -19,6 +19,7 @@ #include #include #include +#include #include using namespace gtsam; diff --git a/examples/ISAM2Example_SmartFactor.cpp b/examples/ISAM2Example_SmartFactor.cpp index 46b9fcd47..21fe6e661 100644 --- a/examples/ISAM2Example_SmartFactor.cpp +++ b/examples/ISAM2Example_SmartFactor.cpp @@ -5,6 +5,7 @@ */ #include +#include #include #include #include diff --git a/examples/ImuFactorExample2.cpp b/examples/ImuFactorExample2.cpp index 4ebc342eb..f83a539af 100644 --- a/examples/ImuFactorExample2.cpp +++ b/examples/ImuFactorExample2.cpp @@ -1,5 +1,6 @@ #include +#include #include #include #include @@ -34,7 +35,7 @@ int main(int argc, char* argv[]) { double radius = 30; const Point3 up(0, 0, 1), target(0, 0, 0); const Point3 position(radius, 0, 0); - const PinholeCamera camera = PinholeCamera::Lookat(position, target, up); + const auto camera = PinholeCamera::Lookat(position, target, up); const auto pose_0 = camera.pose(); // Now, create a constant-twist scenario that makes the camera orbit the diff --git a/gtsam/sam/tests/testRangeFactor.cpp b/gtsam/sam/tests/testRangeFactor.cpp index 0d19918f6..54d4a43c0 100644 --- a/gtsam/sam/tests/testRangeFactor.cpp +++ b/gtsam/sam/tests/testRangeFactor.cpp @@ -356,9 +356,11 @@ TEST(RangeFactor, Point3) { /* ************************************************************************* */ // Do tests with PinholeCamera TEST( RangeFactor, Camera) { - RangeFactor,Point3> factor1(poseKey, pointKey, measurement, model); - RangeFactor,Pose3> factor2(poseKey, pointKey, measurement, model); - RangeFactor,PinholeCamera> factor3(poseKey, pointKey, measurement, model); + using Camera = PinholeCamera; + + RangeFactor factor1(poseKey, pointKey, measurement, model); + RangeFactor factor2(poseKey, pointKey, measurement, model); + RangeFactor factor3(poseKey, pointKey, measurement, model); } /* ************************************************************************* */