diff --git a/.cproject b/.cproject
index 895e2667a..45febcf1b 100644
--- a/.cproject
+++ b/.cproject
@@ -982,6 +982,14 @@
true
true
+
+ make
+ -j5
+ timeAdaptAutoDiff.run
+ true
+ true
+ true
+
make
-j5
diff --git a/gtsam_unstable/nonlinear/ceres_rotation.h b/gtsam_unstable/nonlinear/ceres_rotation.h
index 896761296..83627291c 100644
--- a/gtsam_unstable/nonlinear/ceres_rotation.h
+++ b/gtsam_unstable/nonlinear/ceres_rotation.h
@@ -47,6 +47,7 @@
#include
#include
+#define DCHECK assert
namespace ceres {
diff --git a/gtsam_unstable/timing/timeAdaptAutoDiff.cpp b/gtsam_unstable/timing/timeAdaptAutoDiff.cpp
new file mode 100644
index 000000000..c4ea7a8f3
--- /dev/null
+++ b/gtsam_unstable/timing/timeAdaptAutoDiff.cpp
@@ -0,0 +1,73 @@
+/* ----------------------------------------------------------------------------
+
+ * GTSAM Copyright 2010, Georgia Tech Research Corporation,
+ * Atlanta, Georgia 30332-0415
+ * All Rights Reserved
+ * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
+
+ * See LICENSE for the license information
+
+ * -------------------------------------------------------------------------- */
+
+/**
+ * @file timeCameraExpression.cpp
+ * @brief time CalibratedCamera derivatives
+ * @author Frank Dellaert
+ * @date October 3, 2014
+ */
+
+#include "timeLinearize.h"
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+
+using namespace std;
+using namespace gtsam;
+
+#define time timeMultiThreaded
+
+int main() {
+
+ // The DefaultChart of Camera below is laid out like Snavely's 9-dim vector
+ typedef PinholeCamera Camera;
+ typedef Expression Point2_;
+ typedef Expression Camera_;
+ typedef Expression Point3_;
+
+ // Create leaves
+ Camera_ camera(1);
+ Point3_ point(2);
+
+ // Some parameters needed
+ Point2 z(-17, 30);
+ SharedNoiseModel model = noiseModel::Unit::Create(2);
+
+ // Create values
+ Values values;
+ values.insert(1, Camera());
+ values.insert(2, Point3(0, 0, 1));
+
+ // Dedicated factor
+ NonlinearFactor::shared_ptr f1 = boost::make_shared<
+ GeneralSFMFactor >(z, model, 1, 2);
+ time("GeneralSFMFactor : ", f1, values);
+
+ // AdaptAutoDiff
+ typedef AdaptAutoDiff SnavelyAdaptor;
+ NonlinearFactor::shared_ptr f2 =
+ boost::make_shared >(model, z,
+ Point2_(SnavelyAdaptor(), camera, point));
+ time("Point2_(SnavelyAdaptor(), camera, point): ", f2, values);
+
+ // ExpressionFactor
+ NonlinearFactor::shared_ptr f3 =
+ boost::make_shared >(model, z,
+ Point2_(camera, &Camera::project2, point));
+ time("Point2_(camera, &Camera::project, point): ", f3, values);
+
+ return 0;
+}