diff --git a/.cproject b/.cproject
index ed61e4c4b..9726fec60 100644
--- a/.cproject
+++ b/.cproject
@@ -1027,6 +1027,14 @@
true
true
+
+ make
+ -j4
+ testPinholePose.run
+ true
+ true
+ true
+
make
-j2
@@ -1546,6 +1554,14 @@
true
true
+
+ make
+ -j4
+ testSmartProjectionPoseFactor.run
+ true
+ true
+ true
+
make
-j3
diff --git a/doc/.gitignore b/doc/.gitignore
new file mode 100644
index 000000000..ac7af2e80
--- /dev/null
+++ b/doc/.gitignore
@@ -0,0 +1 @@
+/html/
diff --git a/examples/Pose2SLAMExampleExpressions.cpp b/examples/Pose2SLAMExampleExpressions.cpp
index 92f94c3f3..1f6de6cb1 100644
--- a/examples/Pose2SLAMExampleExpressions.cpp
+++ b/examples/Pose2SLAMExampleExpressions.cpp
@@ -14,20 +14,18 @@
* @brief Expressions version of Pose2SLAMExample.cpp
* @date Oct 2, 2014
* @author Frank Dellaert
- * @author Yong Dian Jian
*/
// The two new headers that allow using our Automatic Differentiation Expression framework
#include
#include
-// Header order is close to far
-#include
+// For an explanation of headers below, please see Pose2SLAMExample.cpp
+#include
+#include
+#include
#include
#include
-#include
-#include
-#include
using namespace std;
using namespace gtsam;
diff --git a/examples/Pose2SLAMExample_g2o.cpp b/examples/Pose2SLAMExample_g2o.cpp
index 564930d74..35f9884e1 100644
--- a/examples/Pose2SLAMExample_g2o.cpp
+++ b/examples/Pose2SLAMExample_g2o.cpp
@@ -20,6 +20,7 @@
#include
#include
+#include
#include
#include
diff --git a/examples/Pose2SLAMExample_graph.cpp b/examples/Pose2SLAMExample_graph.cpp
index 46ca02ee4..c3d901507 100644
--- a/examples/Pose2SLAMExample_graph.cpp
+++ b/examples/Pose2SLAMExample_graph.cpp
@@ -16,11 +16,15 @@
* @author Frank Dellaert
*/
-#include
+// For an explanation of headers below, please see Pose2SLAMExample.cpp
#include
-#include
-#include
+#include
#include
+#include
+#include
+
+// This new header allows us to read examples easily from .graph files
+#include
using namespace std;
using namespace gtsam;
diff --git a/examples/Pose2SLAMExample_graphviz.cpp b/examples/Pose2SLAMExample_graphviz.cpp
index 818a9e577..314ccbdb4 100644
--- a/examples/Pose2SLAMExample_graphviz.cpp
+++ b/examples/Pose2SLAMExample_graphviz.cpp
@@ -16,11 +16,11 @@
* @author Frank Dellaert
*/
+// For an explanation of headers below, please see Pose2SLAMExample.cpp
#include
#include
-#include
-#include
#include
+#include
#include
using namespace std;
diff --git a/examples/Pose2SLAMExample_lago.cpp b/examples/Pose2SLAMExample_lago.cpp
index 9507797eb..b83dfa1db 100644
--- a/examples/Pose2SLAMExample_lago.cpp
+++ b/examples/Pose2SLAMExample_lago.cpp
@@ -22,6 +22,7 @@
#include
#include
#include
+#include
#include
using namespace std;
diff --git a/examples/Pose2SLAMwSPCG.cpp b/examples/Pose2SLAMwSPCG.cpp
index 4422586b0..2c25d2f8e 100644
--- a/examples/Pose2SLAMwSPCG.cpp
+++ b/examples/Pose2SLAMwSPCG.cpp
@@ -16,47 +16,15 @@
* @date June 2, 2012
*/
-/**
- * A simple 2D pose slam example solved using a Conjugate-Gradient method
- * - The robot moves in a 2 meter square
- * - The robot moves 2 meters each step, turning 90 degrees after each step
- * - The robot initially faces along the X axis (horizontal, to the right in 2D)
- * - We have full odometry between pose
- * - We have a loop closure constraint when the robot returns to the first position
- */
-
-// As this is a planar SLAM example, we will use Pose2 variables (x, y, theta) to represent
-// the robot positions
-#include
-#include
-
-// Each variable in the system (poses) must be identified with a unique key.
-// We can either use simple integer keys (1, 2, 3, ...) or symbols (X1, X2, L1).
-// Here we will use simple integer keys
-#include
-
-// In GTSAM, measurement functions are represented as 'factors'. Several common factors
-// have been provided with the library for solving robotics/SLAM/Bundle Adjustment problems.
-// Here we will use Between factors for the relative motion described by odometry measurements.
-// We will also use a Between Factor to encode the loop closure constraint
-// Also, we will initialize the robot at the origin using a Prior factor.
+// For an explanation of headers below, please see Pose2SLAMExample.cpp
#include
#include
-
-// When the factors are created, we will add them to a Factor Graph. As the factors we are using
-// are nonlinear factors, we will need a Nonlinear Factor Graph.
-#include
-
-// The nonlinear solvers within GTSAM are iterative solvers, meaning they linearize the
-// nonlinear functions around an initial linearization point, then solve the linear system
-// to update the linearization point. This happens repeatedly until the solver converges
-// to a consistent set of variable values. This requires us to specify an initial guess
-// for each variable, held in a Values container.
-#include
-
-#include
+#include
#include
+// In contrast to that example, however, we will use a PCG solver here
+#include
+
using namespace std;
using namespace gtsam;
@@ -66,32 +34,24 @@ int main(int argc, char** argv) {
NonlinearFactorGraph graph;
// 2a. Add a prior on the first pose, setting it to the origin
- // A prior factor consists of a mean and a noise model (covariance matrix)
Pose2 prior(0.0, 0.0, 0.0); // prior at origin
noiseModel::Diagonal::shared_ptr priorNoise = noiseModel::Diagonal::Sigmas(Vector3(0.3, 0.3, 0.1));
graph.push_back(PriorFactor(1, prior, priorNoise));
// 2b. Add odometry factors
- // For simplicity, we will use the same noise model for each odometry factor
noiseModel::Diagonal::shared_ptr odometryNoise = noiseModel::Diagonal::Sigmas(Vector3(0.2, 0.2, 0.1));
- // Create odometry (Between) factors between consecutive poses
graph.push_back(BetweenFactor(1, 2, Pose2(2.0, 0.0, M_PI_2), odometryNoise));
graph.push_back(BetweenFactor(2, 3, Pose2(2.0, 0.0, M_PI_2), odometryNoise));
graph.push_back(BetweenFactor(3, 4, Pose2(2.0, 0.0, M_PI_2), odometryNoise));
graph.push_back(BetweenFactor(4, 5, Pose2(2.0, 0.0, M_PI_2), odometryNoise));
// 2c. Add the loop closure constraint
- // This factor encodes the fact that we have returned to the same pose. In real systems,
- // these constraints may be identified in many ways, such as appearance-based techniques
- // with camera images.
- // We will use another Between Factor to enforce this constraint, with the distance set to zero,
noiseModel::Diagonal::shared_ptr model = noiseModel::Diagonal::Sigmas(Vector3(0.2, 0.2, 0.1));
graph.push_back(BetweenFactor(5, 1, Pose2(0.0, 0.0, 0.0), model));
graph.print("\nFactor Graph:\n"); // print
// 3. Create the data structure to hold the initialEstimate estimate to the solution
- // For illustrative purposes, these have been deliberately set to incorrect values
Values initialEstimate;
initialEstimate.insert(1, Pose2(0.5, 0.0, 0.2));
initialEstimate.insert(2, Pose2(2.3, 0.1, 1.1));
@@ -104,15 +64,18 @@ int main(int argc, char** argv) {
LevenbergMarquardtParams parameters;
parameters.verbosity = NonlinearOptimizerParams::ERROR;
parameters.verbosityLM = LevenbergMarquardtParams::LAMBDA;
- parameters.linearSolverType = NonlinearOptimizerParams::Iterative;
- {
- parameters.iterativeParams = boost::make_shared();
- LevenbergMarquardtOptimizer optimizer(graph, initialEstimate, parameters);
- Values result = optimizer.optimize();
- result.print("Final Result:\n");
- cout << "subgraph solver final error = " << graph.error(result) << endl;
- }
+ // LM is still the outer optimization loop, but by specifying "Iterative" below
+ // We indicate that an iterative linear solver should be used.
+ // In addition, the *type* of the iterativeParams decides on the type of
+ // iterative solver, in this case the SPCG (subgraph PCG)
+ parameters.linearSolverType = NonlinearOptimizerParams::Iterative;
+ parameters.iterativeParams = boost::make_shared();
+
+ LevenbergMarquardtOptimizer optimizer(graph, initialEstimate, parameters);
+ Values result = optimizer.optimize();
+ result.print("Final Result:\n");
+ cout << "subgraph solver final error = " << graph.error(result) << endl;
return 0;
}
diff --git a/examples/SFMExample.cpp b/examples/SFMExample.cpp
index 5be266d11..38dd1ca81 100644
--- a/examples/SFMExample.cpp
+++ b/examples/SFMExample.cpp
@@ -15,13 +15,7 @@
* @author Duy-Nguyen Ta
*/
-/**
- * A structure-from-motion example with landmarks
- * - The landmarks form a 10 meter cube
- * - The robot rotates around the landmarks, always facing towards the cube
- */
-
-// For loading the data
+// For loading the data, see the comments therein for scenario (camera rotates around cube)
#include "SFMdata.h"
// Camera observations of landmarks (i.e. pixel coordinates) will be stored as Point2 (x, y).
diff --git a/examples/SFMExample_SmartFactor.cpp b/examples/SFMExample_SmartFactor.cpp
index b999e6600..fce046a59 100644
--- a/examples/SFMExample_SmartFactor.cpp
+++ b/examples/SFMExample_SmartFactor.cpp
@@ -17,51 +17,22 @@
* @author Frank Dellaert
*/
-/**
- * A structure-from-motion example with landmarks
- * - The landmarks form a 10 meter cube
- * - The robot rotates around the landmarks, always facing towards the cube
- */
-
-// For loading the data
-#include "SFMdata.h"
-
-// Camera observations of landmarks (i.e. pixel coordinates) will be stored as Point2 (x, y).
-#include
-
// In GTSAM, measurement functions are represented as 'factors'.
-// The factor we used here is SmartProjectionPoseFactor. Every smart factor represent a single landmark,
-// The SmartProjectionPoseFactor only optimize the pose of camera, not the calibration,
-// The calibration should be known.
+// The factor we used here is SmartProjectionPoseFactor.
+// Every smart factor represent a single landmark, seen from multiple cameras.
+// The SmartProjectionPoseFactor only optimizes for the poses of a camera,
+// not the calibration, which is assumed known.
#include
-// Also, we will initialize the robot at some location using a Prior factor.
-#include
-
-// When the factors are created, we will add them to a Factor Graph. As the factors we are using
-// are nonlinear factors, we will need a Nonlinear Factor Graph.
-#include
-
-// Finally, once all of the factors have been added to our factor graph, we will want to
-// solve/optimize to graph to find the best (Maximum A Posteriori) set of variable values.
-// GTSAM includes several nonlinear optimizers to perform this step. Here we will use a
-// trust-region method known as Powell's Degleg
-#include
-
-// The nonlinear solvers within GTSAM are iterative solvers, meaning they linearize the
-// nonlinear functions around an initial linearization point, then solve the linear system
-// to update the linearization point. This happens repeatedly until the solver converges
-// to a consistent set of variable values. This requires us to specify an initial guess
-// for each variable, held in a Values container.
-#include
-
-#include
+// For an explanation of these headers, see SFMExample.cpp
+#include "SFMdata.h"
+#include
using namespace std;
using namespace gtsam;
// Make the typename short so it looks much cleaner
-typedef gtsam::SmartProjectionPoseFactor SmartFactor;
+typedef SmartProjectionPoseFactor SmartFactor;
/* ************************************************************************* */
int main(int argc, char* argv[]) {
@@ -127,7 +98,8 @@ int main(int argc, char* argv[]) {
initialEstimate.print("Initial Estimates:\n");
// Optimize the graph and print results
- Values result = DoglegOptimizer(graph, initialEstimate).optimize();
+ LevenbergMarquardtOptimizer optimizer(graph, initialEstimate);
+ Values result = optimizer.optimize();
result.print("Final results:\n");
// A smart factor represent the 3D point inside the factor, not as a variable.
@@ -136,20 +108,20 @@ int main(int argc, char* argv[]) {
Values landmark_result;
for (size_t j = 0; j < points.size(); ++j) {
- // The output of point() is in boost::optional, as sometimes
- // the triangulation operation inside smart factor will encounter degeneracy.
- boost::optional point;
-
// The graph stores Factor shared_ptrs, so we cast back to a SmartFactor first
SmartFactor::shared_ptr smart = boost::dynamic_pointer_cast(graph[j]);
if (smart) {
- point = smart->point(result);
+ // The output of point() is in boost::optional, as sometimes
+ // the triangulation operation inside smart factor will encounter degeneracy.
+ boost::optional point = smart->point(result);
if (point) // ignore if boost::optional return NULL
landmark_result.insert(j, *point);
}
}
landmark_result.print("Landmark results:\n");
+ cout << "final error: " << graph.error(result) << endl;
+ cout << "number of iterations: " << optimizer.iterations() << endl;
return 0;
}
diff --git a/examples/SFMExample_SmartFactorPCG.cpp b/examples/SFMExample_SmartFactorPCG.cpp
new file mode 100644
index 000000000..49482292f
--- /dev/null
+++ b/examples/SFMExample_SmartFactorPCG.cpp
@@ -0,0 +1,126 @@
+/* ----------------------------------------------------------------------------
+
+ * 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 SFMExample_SmartFactorPCG.cpp
+ * @brief Version of SFMExample_SmartFactor that uses Preconditioned Conjugate Gradient
+ * @author Frank Dellaert
+ */
+
+// For an explanation of these headers, see SFMExample_SmartFactor.cpp
+#include "SFMdata.h"
+#include
+
+// These extra headers allow us a LM outer loop with PCG linear solver (inner loop)
+#include
+#include
+#include
+
+using namespace std;
+using namespace gtsam;
+
+// Make the typename short so it looks much cleaner
+typedef SmartProjectionPoseFactor SmartFactor;
+
+/* ************************************************************************* */
+int main(int argc, char* argv[]) {
+
+ // Define the camera calibration parameters
+ Cal3_S2::shared_ptr K(new Cal3_S2(50.0, 50.0, 0.0, 50.0, 50.0));
+
+ // Define the camera observation noise model
+ noiseModel::Isotropic::shared_ptr measurementNoise =
+ noiseModel::Isotropic::Sigma(2, 1.0); // one pixel in u and v
+
+ // Create the set of ground-truth landmarks and poses
+ vector points = createPoints();
+ vector poses = createPoses();
+
+ // Create a factor graph
+ NonlinearFactorGraph graph;
+
+ // Simulated measurements from each camera pose, adding them to the factor graph
+ for (size_t j = 0; j < points.size(); ++j) {
+
+ // every landmark represent a single landmark, we use shared pointer to init the factor, and then insert measurements.
+ SmartFactor::shared_ptr smartfactor(new SmartFactor());
+
+ for (size_t i = 0; i < poses.size(); ++i) {
+
+ // generate the 2D measurement
+ SimpleCamera camera(poses[i], *K);
+ Point2 measurement = camera.project(points[j]);
+
+ // call add() function to add measurement into a single factor, here we need to add:
+ smartfactor->add(measurement, i, measurementNoise, K);
+ }
+
+ // insert the smart factor in the graph
+ graph.push_back(smartfactor);
+ }
+
+ // Add a prior on pose x0. This indirectly specifies where the origin is.
+ // 30cm std on x,y,z 0.1 rad on roll,pitch,yaw
+ noiseModel::Diagonal::shared_ptr poseNoise = noiseModel::Diagonal::Sigmas(
+ (Vector(6) << Vector3::Constant(0.3), Vector3::Constant(0.1)).finished());
+ graph.push_back(PriorFactor(0, poses[0], poseNoise));
+
+ // Fix the scale ambiguity by adding a prior
+ graph.push_back(PriorFactor(1, poses[1], poseNoise));
+
+ // Create the initial estimate to the solution
+ Values initialEstimate;
+ Pose3 delta(Rot3::rodriguez(-0.1, 0.2, 0.25), Point3(0.05, -0.10, 0.20));
+ for (size_t i = 0; i < poses.size(); ++i)
+ initialEstimate.insert(i, poses[i].compose(delta));
+
+ // We will use LM in the outer optimization loop, but by specifying "Iterative" below
+ // We indicate that an iterative linear solver should be used.
+ // In addition, the *type* of the iterativeParams decides on the type of
+ // iterative solver, in this case the SPCG (subgraph PCG)
+ LevenbergMarquardtParams parameters;
+ parameters.linearSolverType = NonlinearOptimizerParams::Iterative;
+ parameters.absoluteErrorTol = 1e-10;
+ parameters.relativeErrorTol = 1e-10;
+ parameters.maxIterations = 500;
+ PCGSolverParameters::shared_ptr pcg =
+ boost::make_shared();
+ pcg->preconditioner_ =
+ boost::make_shared();
+ // Following is crucial:
+ pcg->setEpsilon_abs(1e-10);
+ pcg->setEpsilon_rel(1e-10);
+ parameters.iterativeParams = pcg;
+
+ LevenbergMarquardtOptimizer optimizer(graph, initialEstimate, parameters);
+ Values result = optimizer.optimize();
+
+ // Display result as in SFMExample_SmartFactor.run
+ result.print("Final results:\n");
+ Values landmark_result;
+ for (size_t j = 0; j < points.size(); ++j) {
+ SmartFactor::shared_ptr smart = //
+ boost::dynamic_pointer_cast(graph[j]);
+ if (smart) {
+ boost::optional point = smart->point(result);
+ if (point) // ignore if boost::optional return NULL
+ landmark_result.insert(j, *point);
+ }
+ }
+
+ landmark_result.print("Landmark results:\n");
+ cout << "final error: " << graph.error(result) << endl;
+ cout << "number of iterations: " << optimizer.iterations() << endl;
+
+ return 0;
+}
+/* ************************************************************************* */
+
diff --git a/gtsam.h b/gtsam.h
index c5528309e..f8e0af28e 100644
--- a/gtsam.h
+++ b/gtsam.h
@@ -2310,23 +2310,23 @@ virtual class GeneralSFMFactor2 : gtsam::NoiseModelFactor {
};
#include
-template
+template
virtual class SmartProjectionPoseFactor : gtsam::NonlinearFactor {
SmartProjectionPoseFactor(double rankTol, double linThreshold,
- bool manageDegeneracy, bool enableEPI, const POSE& body_P_sensor);
+ bool manageDegeneracy, bool enableEPI, const gtsam::Pose3& body_P_sensor);
SmartProjectionPoseFactor(double rankTol);
SmartProjectionPoseFactor();
- void add(const gtsam::Point2& measured_i, size_t poseKey_i, const gtsam::noiseModel::Base* noise_i,
- const CALIBRATION* K_i);
+ void add(const gtsam::Point2& measured_i, size_t poseKey_i,
+ const gtsam::noiseModel::Base* noise_i, const CALIBRATION* K_i);
// enabling serialization functionality
//void serialize() const;
};
-typedef gtsam::SmartProjectionPoseFactor SmartProjectionPose3Factor;
+typedef gtsam::SmartProjectionPoseFactor SmartProjectionPose3Factor;
#include
diff --git a/gtsam/discrete/DecisionTree-inl.h b/gtsam/discrete/DecisionTree-inl.h
index 9319a1541..cd56780e5 100644
--- a/gtsam/discrete/DecisionTree-inl.h
+++ b/gtsam/discrete/DecisionTree-inl.h
@@ -462,15 +462,17 @@ namespace gtsam {
// cannot just create a root Choice node on the label: if the label is not the
// highest label, we need to do a complicated and expensive recursive call.
template template
- typename DecisionTree::NodePtr DecisionTree::compose(
- Iterator begin, Iterator end, const L& label) const {
+ typename DecisionTree::NodePtr DecisionTree::compose(Iterator begin,
+ Iterator end, const L& label) const {
// find highest label among branches
boost::optional highestLabel;
boost::optional nrChoices;
for (Iterator it = begin; it != end; it++) {
- if (it->root_->isLeaf()) continue;
- boost::shared_ptr c = boost::dynamic_pointer_cast (it->root_);
+ if (it->root_->isLeaf())
+ continue;
+ boost::shared_ptr c =
+ boost::dynamic_pointer_cast(it->root_);
if (!highestLabel || c->label() > *highestLabel) {
highestLabel.reset(c->label());
nrChoices.reset(c->nrChoices());
@@ -478,30 +480,31 @@ namespace gtsam {
}
// if label is already in correct order, just put together a choice on label
- if (!highestLabel || label > *highestLabel) {
+ if (!highestLabel || !nrChoices || label > *highestLabel) {
boost::shared_ptr choiceOnLabel(new Choice(label, end - begin));
for (Iterator it = begin; it != end; it++)
choiceOnLabel->push_back(it->root_);
return Choice::Unique(choiceOnLabel);
- }
-
- // Set up a new choice on the highest label
- boost::shared_ptr choiceOnHighestLabel(new Choice(*highestLabel, *nrChoices));
- // now, for all possible values of highestLabel
- for (size_t index = 0; index < *nrChoices; index++) {
- // make a new set of functions for composing by iterating over the given
- // functions, and selecting the appropriate branch.
- std::vector functions;
- for (Iterator it = begin; it != end; it++) {
- // by restricting the input functions to value i for labelBelow
- DecisionTree chosen = it->choose(*highestLabel, index);
- functions.push_back(chosen);
+ } else {
+ // Set up a new choice on the highest label
+ boost::shared_ptr choiceOnHighestLabel(
+ new Choice(*highestLabel, *nrChoices));
+ // now, for all possible values of highestLabel
+ for (size_t index = 0; index < *nrChoices; index++) {
+ // make a new set of functions for composing by iterating over the given
+ // functions, and selecting the appropriate branch.
+ std::vector functions;
+ for (Iterator it = begin; it != end; it++) {
+ // by restricting the input functions to value i for labelBelow
+ DecisionTree chosen = it->choose(*highestLabel, index);
+ functions.push_back(chosen);
+ }
+ // We then recurse, for all values of the highest label
+ NodePtr fi = compose(functions.begin(), functions.end(), label);
+ choiceOnHighestLabel->push_back(fi);
}
- // We then recurse, for all values of the highest label
- NodePtr fi = compose(functions.begin(), functions.end(), label);
- choiceOnHighestLabel->push_back(fi);
+ return Choice::Unique(choiceOnHighestLabel);
}
- return Choice::Unique(choiceOnHighestLabel);
}
/*********************************************************************************/
@@ -667,9 +670,10 @@ namespace gtsam {
void DecisionTree::dot(const std::string& name, bool showZero) const {
std::ofstream os((name + ".dot").c_str());
dot(os, showZero);
- system(
+ int result = system(
("dot -Tpdf " + name + ".dot -o " + name + ".pdf >& /dev/null").c_str());
- }
+ if (result==-1) throw std::runtime_error("DecisionTree::dot system call failed");
+}
/*********************************************************************************/
diff --git a/gtsam/geometry/CalibratedCamera.cpp b/gtsam/geometry/CalibratedCamera.cpp
index 1f5f1f8a5..e0d57feff 100644
--- a/gtsam/geometry/CalibratedCamera.cpp
+++ b/gtsam/geometry/CalibratedCamera.cpp
@@ -19,88 +19,134 @@
#include
#include
+using namespace std;
+
namespace gtsam {
+#ifndef PINHOLEBASE_LINKING_FIX
/* ************************************************************************* */
-CalibratedCamera::CalibratedCamera(const Pose3& pose) :
- pose_(pose) {
+Matrix26 PinholeBase::Dpose(const Point2& pn, double d) {
+ // optimized version of derivatives, see CalibratedCamera.nb
+ const double u = pn.x(), v = pn.y();
+ double uv = u * v, uu = u * u, vv = v * v;
+ Matrix26 Dpn_pose;
+ Dpn_pose << uv, -1 - uu, v, -d, 0, d * u, 1 + vv, -uv, -u, 0, -d, d * v;
+ return Dpn_pose;
}
/* ************************************************************************* */
-CalibratedCamera::CalibratedCamera(const Vector &v) :
- pose_(Pose3::Expmap(v)) {
+Matrix23 PinholeBase::Dpoint(const Point2& pn, double d, const Matrix3& Rt) {
+ // optimized version of derivatives, see CalibratedCamera.nb
+ const double u = pn.x(), v = pn.y();
+ Matrix23 Dpn_point;
+ Dpn_point << //
+ Rt(0, 0) - u * Rt(2, 0), Rt(0, 1) - u * Rt(2, 1), Rt(0, 2) - u * Rt(2, 2), //
+ /**/Rt(1, 0) - v * Rt(2, 0), Rt(1, 1) - v * Rt(2, 1), Rt(1, 2) - v * Rt(2, 2);
+ Dpn_point *= d;
+ return Dpn_point;
}
/* ************************************************************************* */
-Point2 CalibratedCamera::project_to_camera(const Point3& P,
- OptionalJacobian<2,3> H1) {
- if (H1) {
- double d = 1.0 / P.z(), d2 = d * d;
- *H1 << d, 0.0, -P.x() * d2, 0.0, d, -P.y() * d2;
+Pose3 PinholeBase::LevelPose(const Pose2& pose2, double height) {
+ const double st = sin(pose2.theta()), ct = cos(pose2.theta());
+ const Point3 x(st, -ct, 0), y(0, 0, -1), z(ct, st, 0);
+ const Rot3 wRc(x, y, z);
+ const Point3 t(pose2.x(), pose2.y(), height);
+ return Pose3(wRc, t);
+}
+
+/* ************************************************************************* */
+Pose3 PinholeBase::LookatPose(const Point3& eye, const Point3& target,
+ const Point3& upVector) {
+ Point3 zc = target - eye;
+ zc = zc / zc.norm();
+ Point3 xc = (-upVector).cross(zc); // minus upVector since yc is pointing down
+ xc = xc / xc.norm();
+ Point3 yc = zc.cross(xc);
+ return Pose3(Rot3(xc, yc, zc), eye);
+}
+
+/* ************************************************************************* */
+bool PinholeBase::equals(const PinholeBase &camera, double tol) const {
+ return pose_.equals(camera.pose(), tol);
+}
+
+/* ************************************************************************* */
+void PinholeBase::print(const string& s) const {
+ pose_.print(s + ".pose");
+}
+
+/* ************************************************************************* */
+const Pose3& PinholeBase::getPose(OptionalJacobian<6, 6> H) const {
+ if (H) {
+ H->setZero();
+ H->block(0, 0, 6, 6) = I_6x6;
}
- return Point2(P.x() / P.z(), P.y() / P.z());
+ return pose_;
}
/* ************************************************************************* */
-Point3 CalibratedCamera::backproject_from_camera(const Point2& p,
- const double scale) {
- return Point3(p.x() * scale, p.y() * scale, scale);
+Point2 PinholeBase::project_to_camera(const Point3& pc,
+ OptionalJacobian<2, 3> Dpoint) {
+ double d = 1.0 / pc.z();
+ const double u = pc.x() * d, v = pc.y() * d;
+ if (Dpoint)
+ *Dpoint << d, 0.0, -u * d, 0.0, d, -v * d;
+ return Point2(u, v);
}
+/* ************************************************************************* */
+pair PinholeBase::projectSafe(const Point3& pw) const {
+ const Point3 pc = pose().transform_to(pw);
+ const Point2 pn = project_to_camera(pc);
+ return make_pair(pn, pc.z() > 0);
+}
+
+/* ************************************************************************* */
+Point2 PinholeBase::project2(const Point3& point, OptionalJacobian<2, 6> Dpose,
+ OptionalJacobian<2, 3> Dpoint) const {
+
+ Matrix3 Rt; // calculated by transform_to if needed
+ const Point3 q = pose().transform_to(point, boost::none, Dpoint ? &Rt : 0);
+#ifdef GTSAM_THROW_CHEIRALITY_EXCEPTION
+ if (q.z() <= 0)
+ throw CheiralityException();
+#endif
+ const Point2 pn = project_to_camera(q);
+
+ if (Dpose || Dpoint) {
+ const double d = 1.0 / q.z();
+ if (Dpose)
+ *Dpose = PinholeBase::Dpose(pn, d);
+ if (Dpoint)
+ *Dpoint = PinholeBase::Dpoint(pn, d, Rt);
+ }
+ return pn;
+}
+
+/* ************************************************************************* */
+Point3 PinholeBase::backproject_from_camera(const Point2& p,
+ const double depth) {
+ return Point3(p.x() * depth, p.y() * depth, depth);
+}
+
+#endif
+
/* ************************************************************************* */
CalibratedCamera CalibratedCamera::Level(const Pose2& pose2, double height) {
- double st = sin(pose2.theta()), ct = cos(pose2.theta());
- Point3 x(st, -ct, 0), y(0, 0, -1), z(ct, st, 0);
- Rot3 wRc(x, y, z);
- Point3 t(pose2.x(), pose2.y(), height);
- Pose3 pose3(wRc, t);
- return CalibratedCamera(pose3);
+ return CalibratedCamera(LevelPose(pose2, height));
+}
+
+/* ************************************************************************* */
+CalibratedCamera CalibratedCamera::Lookat(const Point3& eye,
+ const Point3& target, const Point3& upVector) {
+ return CalibratedCamera(LookatPose(eye, target, upVector));
}
/* ************************************************************************* */
Point2 CalibratedCamera::project(const Point3& point,
- OptionalJacobian<2,6> Dpose, OptionalJacobian<2,3> Dpoint) const {
-
-#ifdef CALIBRATEDCAMERA_CHAIN_RULE
- Matrix36 Dpose_;
- Matrix3 Dpoint_;
- Point3 q = pose_.transform_to(point, Dpose ? Dpose_ : 0, Dpoint ? Dpoint_ : 0);
-#else
- Point3 q = pose_.transform_to(point);
-#endif
- Point2 intrinsic = project_to_camera(q);
-
- // Check if point is in front of camera
- if (q.z() <= 0)
- throw CheiralityException();
-
- if (Dpose || Dpoint) {
-#ifdef CALIBRATEDCAMERA_CHAIN_RULE
- // just implement chain rule
- if(Dpose && Dpoint) {
- Matrix23 H;
- project_to_camera(q,H);
- if (Dpose) *Dpose = H * (*Dpose_);
- if (Dpoint) *Dpoint = H * (*Dpoint_);
- }
-#else
- // optimized version, see CalibratedCamera.nb
- const double z = q.z(), d = 1.0 / z;
- const double u = intrinsic.x(), v = intrinsic.y(), uv = u * v;
- if (Dpose)
- *Dpose << uv, -(1. + u * u), v, -d, 0., d * u, (1. + v * v),
- -uv, -u, 0., -d, d * v;
- if (Dpoint) {
- const Matrix3 R(pose_.rotation().matrix());
- Matrix23 Dpoint_;
- Dpoint_ << R(0, 0) - u * R(0, 2), R(1, 0) - u * R(1, 2),
- R(2, 0) - u * R(2, 2), R(0, 1) - v * R(0, 2),
- R(1, 1) - v * R(1, 2), R(2, 1) - v * R(2, 2);
- *Dpoint = d * Dpoint_;
- }
-#endif
- }
- return intrinsic;
+ OptionalJacobian<2, 6> Dcamera, OptionalJacobian<2, 3> Dpoint) const {
+ return project2(point, Dcamera, Dpoint);
}
/* ************************************************************************* */
diff --git a/gtsam/geometry/CalibratedCamera.h b/gtsam/geometry/CalibratedCamera.h
index 9e907f1d5..0e6f83fdf 100644
--- a/gtsam/geometry/CalibratedCamera.h
+++ b/gtsam/geometry/CalibratedCamera.h
@@ -19,10 +19,14 @@
#pragma once
#include
-#include
-
+#define PINHOLEBASE_LINKING_FIX
+#ifdef PINHOLEBASE_LINKING_FIX
+#include
+#endif
namespace gtsam {
+class Point2;
+
class GTSAM_EXPORT CheiralityException: public ThreadsafeException<
CheiralityException> {
public:
@@ -31,6 +35,275 @@ public:
}
};
+/**
+ * A pinhole camera class that has a Pose3, functions as base class for all pinhole cameras
+ * @addtogroup geometry
+ * \nosubgrouping
+ */
+class GTSAM_EXPORT PinholeBase {
+
+private:
+
+ Pose3 pose_; ///< 3D pose of camera
+
+#ifndef PINHOLEBASE_LINKING_FIX
+
+protected:
+
+ /// @name Derivatives
+ /// @{
+
+ /**
+ * Calculate Jacobian with respect to pose
+ * @param pn projection in normalized coordinates
+ * @param d disparity (inverse depth)
+ */
+ static Matrix26 Dpose(const Point2& pn, double d);
+
+ /**
+ * Calculate Jacobian with respect to point
+ * @param pn projection in normalized coordinates
+ * @param d disparity (inverse depth)
+ * @param Rt transposed rotation matrix
+ */
+ static Matrix23 Dpoint(const Point2& pn, double d, const Matrix3& Rt);
+
+ /// @}
+
+public:
+
+ /// @name Static functions
+ /// @{
+
+ /**
+ * Create a level pose at the given 2D pose and height
+ * @param K the calibration
+ * @param pose2 specifies the location and viewing direction
+ * (theta 0 = looking in direction of positive X axis)
+ * @param height camera height
+ */
+ static Pose3 LevelPose(const Pose2& pose2, double height);
+
+ /**
+ * Create a camera pose at the given eye position looking at a target point in the scene
+ * with the specified up direction vector.
+ * @param eye specifies the camera position
+ * @param target the point to look at
+ * @param upVector specifies the camera up direction vector,
+ * doesn't need to be on the image plane nor orthogonal to the viewing axis
+ */
+ static Pose3 LookatPose(const Point3& eye, const Point3& target,
+ const Point3& upVector);
+
+ /// @}
+ /// @name Standard Constructors
+ /// @{
+
+ /** default constructor */
+ PinholeBase() {
+ }
+
+ /** constructor with pose */
+ explicit PinholeBase(const Pose3& pose) :
+ pose_(pose) {
+ }
+
+ /// @}
+ /// @name Advanced Constructors
+ /// @{
+
+ explicit PinholeBase(const Vector &v) :
+ pose_(Pose3::Expmap(v)) {
+ }
+
+ /// @}
+ /// @name Testable
+ /// @{
+
+ /// assert equality up to a tolerance
+ bool equals(const PinholeBase &camera, double tol = 1e-9) const;
+
+ /// print
+ void print(const std::string& s = "PinholeBase") const;
+
+ /// @}
+ /// @name Standard Interface
+ /// @{
+
+ /// return pose, constant version
+ const Pose3& pose() const {
+ return pose_;
+ }
+
+ /// return pose, with derivative
+ const Pose3& getPose(OptionalJacobian<6, 6> H) const;
+
+ /// @}
+ /// @name Transformations and measurement functions
+ /// @{
+
+ /**
+ * Project from 3D point in camera coordinates into image
+ * Does *not* throw a CheiralityException, even if pc behind image plane
+ * @param pc point in camera coordinates
+ */
+ static Point2 project_to_camera(const Point3& pc, //
+ OptionalJacobian<2, 3> Dpoint = boost::none);
+
+ /// Project a point into the image and check depth
+ std::pair projectSafe(const Point3& pw) const;
+
+ /**
+ * Project point into the image
+ * Throws a CheiralityException if point behind image plane iff GTSAM_THROW_CHEIRALITY_EXCEPTION
+ * @param point 3D point in world coordinates
+ * @return the intrinsic coordinates of the projected point
+ */
+ Point2 project2(const Point3& point, OptionalJacobian<2, 6> Dpose =
+ boost::none, OptionalJacobian<2, 3> Dpoint = boost::none) const;
+
+ /// backproject a 2-dimensional point to a 3-dimensional point at given depth
+ static Point3 backproject_from_camera(const Point2& p, const double depth);
+
+#else
+
+public:
+
+ PinholeBase() {
+ }
+
+ explicit PinholeBase(const Pose3& pose) :
+ pose_(pose) {
+ }
+
+ explicit PinholeBase(const Vector &v) :
+ pose_(Pose3::Expmap(v)) {
+ }
+
+ const Pose3& pose() const {
+ return pose_;
+ }
+
+ /* ************************************************************************* */
+ static Matrix26 Dpose(const Point2& pn, double d) {
+ // optimized version of derivatives, see CalibratedCamera.nb
+ const double u = pn.x(), v = pn.y();
+ double uv = u * v, uu = u * u, vv = v * v;
+ Matrix26 Dpn_pose;
+ Dpn_pose << uv, -1 - uu, v, -d, 0, d * u, 1 + vv, -uv, -u, 0, -d, d * v;
+ return Dpn_pose;
+ }
+
+ /* ************************************************************************* */
+ static Matrix23 Dpoint(const Point2& pn, double d, const Matrix3& Rt) {
+ // optimized version of derivatives, see CalibratedCamera.nb
+ const double u = pn.x(), v = pn.y();
+ Matrix23 Dpn_point;
+ Dpn_point << //
+ Rt(0, 0) - u * Rt(2, 0), Rt(0, 1) - u * Rt(2, 1), Rt(0, 2) - u * Rt(2, 2), //
+ /**/Rt(1, 0) - v * Rt(2, 0), Rt(1, 1) - v * Rt(2, 1), Rt(1, 2) - v * Rt(2, 2);
+ Dpn_point *= d;
+ return Dpn_point;
+ }
+
+ /* ************************************************************************* */
+ static Pose3 LevelPose(const Pose2& pose2, double height) {
+ const double st = sin(pose2.theta()), ct = cos(pose2.theta());
+ const Point3 x(st, -ct, 0), y(0, 0, -1), z(ct, st, 0);
+ const Rot3 wRc(x, y, z);
+ const Point3 t(pose2.x(), pose2.y(), height);
+ return Pose3(wRc, t);
+ }
+
+ /* ************************************************************************* */
+ static Pose3 LookatPose(const Point3& eye, const Point3& target,
+ const Point3& upVector) {
+ Point3 zc = target - eye;
+ zc = zc / zc.norm();
+ Point3 xc = (-upVector).cross(zc); // minus upVector since yc is pointing down
+ xc = xc / xc.norm();
+ Point3 yc = zc.cross(xc);
+ return Pose3(Rot3(xc, yc, zc), eye);
+ }
+
+ /* ************************************************************************* */
+ bool equals(const PinholeBase &camera, double tol=1e-9) const {
+ return pose_.equals(camera.pose(), tol);
+ }
+
+ /* ************************************************************************* */
+ void print(const std::string& s) const {
+ pose_.print(s + ".pose");
+ }
+
+ /* ************************************************************************* */
+ const Pose3& getPose(OptionalJacobian<6, 6> H) const {
+ if (H) {
+ H->setZero();
+ H->block(0, 0, 6, 6) = I_6x6;
+ }
+ return pose_;
+ }
+
+ /* ************************************************************************* */
+ static Point2 project_to_camera(const Point3& pc,
+ OptionalJacobian<2, 3> Dpoint = boost::none) {
+ double d = 1.0 / pc.z();
+ const double u = pc.x() * d, v = pc.y() * d;
+ if (Dpoint)
+ *Dpoint << d, 0.0, -u * d, 0.0, d, -v * d;
+ return Point2(u, v);
+ }
+
+ /* ************************************************************************* */
+ std::pair projectSafe(const Point3& pw) const {
+ const Point3 pc = pose().transform_to(pw);
+ const Point2 pn = project_to_camera(pc);
+ return std::make_pair(pn, pc.z() > 0);
+ }
+
+ /* ************************************************************************* */
+ Point2 project2(const Point3& point, OptionalJacobian<2, 6> Dpose,
+ OptionalJacobian<2, 3> Dpoint) const {
+
+ Matrix3 Rt; // calculated by transform_to if needed
+ const Point3 q = pose().transform_to(point, boost::none, Dpoint ? &Rt : 0);
+ #ifdef GTSAM_THROW_CHEIRALITY_EXCEPTION
+ if (q.z() <= 0)
+ throw CheiralityException();
+ #endif
+ const Point2 pn = project_to_camera(q);
+
+ if (Dpose || Dpoint) {
+ const double d = 1.0 / q.z();
+ if (Dpose)
+ *Dpose = PinholeBase::Dpose(pn, d);
+ if (Dpoint)
+ *Dpoint = PinholeBase::Dpoint(pn, d, Rt);
+ }
+ return pn;
+ }
+
+ /* ************************************************************************* */
+ static Point3 backproject_from_camera(const Point2& p,
+ const double depth) {
+ return Point3(p.x() * depth, p.y() * depth, depth);
+ }
+
+#endif
+
+private:
+
+ /** Serialization function */
+ friend class boost::serialization::access;
+ template
+ void serialize(Archive & ar, const unsigned int version) {
+ ar & BOOST_SERIALIZATION_NVP(pose_);
+ }
+
+};
+// end of class PinholeBase
+
/**
* A Calibrated camera class [R|-R't], calibration K=I.
* If calibration is known, it is more computationally efficient
@@ -38,13 +311,13 @@ public:
* @addtogroup geometry
* \nosubgrouping
*/
-class GTSAM_EXPORT CalibratedCamera {
-private:
- Pose3 pose_; // 6DOF pose
+class GTSAM_EXPORT CalibratedCamera: public PinholeBase {
public:
- enum { dimension = 6 };
+ enum {
+ dimension = 6
+ };
/// @name Standard Constructors
/// @{
@@ -54,26 +327,40 @@ public:
}
/// construct with pose
- explicit CalibratedCamera(const Pose3& pose);
+ explicit CalibratedCamera(const Pose3& pose) :
+ PinholeBase(pose) {
+ }
+
+ /// @}
+ /// @name Named Constructors
+ /// @{
+
+ /**
+ * Create a level camera at the given 2D pose and height
+ * @param pose2 specifies the location and viewing direction
+ * @param height specifies the height of the camera (along the positive Z-axis)
+ * (theta 0 = looking in direction of positive X axis)
+ */
+ static CalibratedCamera Level(const Pose2& pose2, double height);
+
+ /**
+ * Create a camera at the given eye position looking at a target point in the scene
+ * with the specified up direction vector.
+ * @param eye specifies the camera position
+ * @param target the point to look at
+ * @param upVector specifies the camera up direction vector,
+ * doesn't need to be on the image plane nor orthogonal to the viewing axis
+ */
+ static CalibratedCamera Lookat(const Point3& eye, const Point3& target,
+ const Point3& upVector);
/// @}
/// @name Advanced Constructors
/// @{
/// construct from vector
- explicit CalibratedCamera(const Vector &v);
-
- /// @}
- /// @name Testable
- /// @{
-
- virtual void print(const std::string& s = "") const {
- pose_.print(s);
- }
-
- /// check equality to another camera
- bool equals(const CalibratedCamera &camera, double tol = 1e-9) const {
- return pose_.equals(camera.pose(), tol);
+ explicit CalibratedCamera(const Vector &v) :
+ PinholeBase(v) {
}
/// @}
@@ -84,19 +371,6 @@ public:
virtual ~CalibratedCamera() {
}
- /// return pose
- inline const Pose3& pose() const {
- return pose_;
- }
-
- /**
- * Create a level camera at the given 2D pose and height
- * @param pose2 specifies the location and viewing direction
- * @param height specifies the height of the camera (along the positive Z-axis)
- * (theta 0 = looking in direction of positive X axis)
- */
- static CalibratedCamera Level(const Pose2& pose2, double height);
-
/// @}
/// @name Manifold
/// @{
@@ -107,87 +381,68 @@ public:
/// Return canonical coordinate
Vector localCoordinates(const CalibratedCamera& T2) const;
- /// Lie group dimensionality
+ /// @deprecated
inline size_t dim() const {
return 6;
}
- /// Lie group dimensionality
+ /// @deprecated
inline static size_t Dim() {
return 6;
}
- /* ************************************************************************* */
- // measurement functions and derivatives
- /* ************************************************************************* */
-
/// @}
/// @name Transformations and mesaurement functions
/// @{
- /**
- * This function receives the camera pose and the landmark location and
- * returns the location the point is supposed to appear in the image
- * @param point a 3D point to be projected
- * @param Dpose the optionally computed Jacobian with respect to pose
- * @param Dpoint the optionally computed Jacobian with respect to the 3D point
- * @return the intrinsic coordinates of the projected point
- */
- Point2 project(const Point3& point,
- OptionalJacobian<2, 6> Dpose = boost::none,
- OptionalJacobian<2, 3> Dpoint = boost::none) const;
/**
- * projects a 3-dimensional point in camera coordinates into the
- * camera and returns a 2-dimensional point, no calibration applied
- * With optional 2by3 derivative
+ * @deprecated
+ * Use project2, which is more consistently named across Pinhole cameras
*/
- static Point2 project_to_camera(const Point3& cameraPoint,
- OptionalJacobian<2, 3> H1 = boost::none);
+ Point2 project(const Point3& point, OptionalJacobian<2, 6> Dcamera =
+ boost::none, OptionalJacobian<2, 3> Dpoint = boost::none) const;
- /**
- * backproject a 2-dimensional point to a 3-dimension point
- */
- static Point3 backproject_from_camera(const Point2& p, const double scale);
+ /// backproject a 2-dimensional point to a 3-dimensional point at given depth
+ Point3 backproject(const Point2& pn, double depth) const {
+ return pose().transform_from(backproject_from_camera(pn, depth));
+ }
/**
* Calculate range to a landmark
* @param point 3D location of landmark
- * @param H1 optionally computed Jacobian with respect to pose
- * @param H2 optionally computed Jacobian with respect to the 3D point
* @return range (double)
*/
- double range(const Point3& point, OptionalJacobian<1, 6> H1 = boost::none,
- OptionalJacobian<1, 3> H2 = boost::none) const {
- return pose_.range(point, H1, H2);
+ double range(const Point3& point,
+ OptionalJacobian<1, 6> Dcamera = boost::none,
+ OptionalJacobian<1, 3> Dpoint = boost::none) const {
+ return pose().range(point, Dcamera, Dpoint);
}
/**
* Calculate range to another pose
* @param pose Other SO(3) pose
- * @param H1 optionally computed Jacobian with respect to pose
- * @param H2 optionally computed Jacobian with respect to the 3D point
* @return range (double)
*/
- double range(const Pose3& pose, OptionalJacobian<1, 6> H1 = boost::none,
- OptionalJacobian<1, 6> H2 = boost::none) const {
- return pose_.range(pose, H1, H2);
+ double range(const Pose3& pose, OptionalJacobian<1, 6> Dcamera = boost::none,
+ OptionalJacobian<1, 6> Dpose = boost::none) const {
+ return this->pose().range(pose, Dcamera, Dpose);
}
/**
* Calculate range to another camera
* @param camera Other camera
- * @param H1 optionally computed Jacobian with respect to pose
- * @param H2 optionally computed Jacobian with respect to the 3D point
* @return range (double)
*/
- double range(const CalibratedCamera& camera, OptionalJacobian<1, 6> H1 =
- boost::none, OptionalJacobian<1, 6> H2 = boost::none) const {
- return pose_.range(camera.pose_, H1, H2);
+ double range(const CalibratedCamera& camera, //
+ OptionalJacobian<1, 6> H1 = boost::none, //
+ OptionalJacobian<1, 6> H2 = boost::none) const {
+ return pose().range(camera.pose(), H1, H2);
}
+ /// @}
+
private:
- /// @}
/// @name Advanced Interface
/// @{
@@ -195,17 +450,22 @@ private:
friend class boost::serialization::access;
template
void serialize(Archive & ar, const unsigned int version) {
- ar & BOOST_SERIALIZATION_NVP(pose_);
+ ar
+ & boost::serialization::make_nvp("PinholeBase",
+ boost::serialization::base_object(*this));
}
/// @}
};
template<>
-struct traits : public internal::Manifold {};
+struct traits : public internal::Manifold {
+};
template<>
-struct traits : public internal::Manifold {};
+struct traits : public internal::Manifold<
+ CalibratedCamera> {
+};
}
diff --git a/gtsam/geometry/CameraSet.h b/gtsam/geometry/CameraSet.h
new file mode 100644
index 000000000..3a34ca1fd
--- /dev/null
+++ b/gtsam/geometry/CameraSet.h
@@ -0,0 +1,123 @@
+/* ----------------------------------------------------------------------------
+
+ * 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 CameraSet.h
+ * @brief Base class to create smart factors on poses or cameras
+ * @author Frank Dellaert
+ * @date Feb 19, 2015
+ */
+
+#pragma once
+
+#include
+#include // for Cheirality exception
+#include
+#include
+
+namespace gtsam {
+
+/**
+ * @brief A set of cameras, all with their own calibration
+ * Assumes that a camera is laid out as 6 Pose3 parameters then calibration
+ */
+template
+class CameraSet: public std::vector {
+
+protected:
+
+ /**
+ * 2D measurement and noise model for each of the m views
+ * The order is kept the same as the keys that we use to create the factor.
+ */
+ typedef typename CAMERA::Measurement Z;
+
+ static const int ZDim = traits::dimension; ///< Measurement dimension
+ static const int Dim = traits::dimension; ///< Camera dimension
+
+public:
+
+ /// Definitions for blocks of F
+ typedef Eigen::Matrix MatrixZD; // F
+ typedef std::pair FBlock; // Fblocks
+
+ /**
+ * print
+ * @param s optional string naming the factor
+ * @param keyFormatter optional formatter useful for printing Symbols
+ */
+ void print(const std::string& s = "") const {
+ std::cout << s << "CameraSet, cameras = \n";
+ for (size_t k = 0; k < this->size(); ++k)
+ this->at(k).print();
+ }
+
+ /// equals
+ virtual bool equals(const CameraSet& p, double tol = 1e-9) const {
+ if (this->size() != p.size())
+ return false;
+ bool camerasAreEqual = true;
+ for (size_t i = 0; i < this->size(); i++) {
+ if (this->at(i).equals(p.at(i), tol) == false)
+ camerasAreEqual = false;
+ break;
+ }
+ return camerasAreEqual;
+ }
+
+ /**
+ * Project a point, with derivatives in this, point, and calibration
+ * throws CheiralityException
+ */
+ std::vector project(const Point3& point, boost::optional F =
+ boost::none, boost::optional E = boost::none,
+ boost::optional H = boost::none) const {
+
+ size_t nrCameras = this->size();
+ if (F) F->resize(ZDim * nrCameras, 6);
+ if (E) E->resize(ZDim * nrCameras, 3);
+ if (H && Dim > 6) H->resize(ZDim * nrCameras, Dim - 6);
+ std::vector z(nrCameras);
+
+ for (size_t i = 0; i < nrCameras; i++) {
+ Eigen::Matrix Fi;
+ Eigen::Matrix Ei;
+ Eigen::Matrix Hi;
+ z[i] = this->at(i).project(point, F ? &Fi : 0, E ? &Ei : 0, H ? &Hi : 0);
+ if (F) F->block(ZDim * i, 0) = Fi;
+ if (E) E->block(ZDim * i, 0) = Ei;
+ if (H) H->block(ZDim * i, 0) = Hi;
+ }
+ return z;
+ }
+
+private:
+
+ /// Serialization function
+ friend class boost::serialization::access;
+ template
+ void serialize(ARCHIVE & ar, const unsigned int version) {
+ ar & (*this);
+ }
+};
+
+template
+const int CameraSet::ZDim;
+
+template
+struct traits > : public Testable > {
+};
+
+template
+struct traits > : public Testable > {
+};
+
+} // \ namespace gtsam
diff --git a/gtsam/geometry/PinholeCamera.h b/gtsam/geometry/PinholeCamera.h
index 46df47ecb..bfc2bbb93 100644
--- a/gtsam/geometry/PinholeCamera.h
+++ b/gtsam/geometry/PinholeCamera.h
@@ -18,32 +18,40 @@
#pragma once
-#include
-#include
-#include
+#include
namespace gtsam {
/**
* A pinhole camera class that has a Pose3 and a Calibration.
+ * Use PinholePose if you will not be optimizing for Calibration
* @addtogroup geometry
* \nosubgrouping
*/
template
-class PinholeCamera {
+class GTSAM_EXPORT PinholeCamera: public PinholeBaseK {
+
+public:
+
+ /**
+ * Some classes template on either PinholeCamera or StereoCamera,
+ * and this typedef informs those classes what "project" returns.
+ */
+ typedef Point2 Measurement;
private:
- Pose3 pose_;
- Calibration K_;
- GTSAM_CONCEPT_MANIFOLD_TYPE(Calibration)
+ typedef PinholeBaseK Base; ///< base class has 3D pose as private member
+ Calibration K_; ///< Calibration, part of class now
// Get dimensions of calibration type at compile time
static const int DimK = FixedDimension::value;
public:
- enum { dimension = 6 + DimK };
+ enum {
+ dimension = 6 + DimK
+ }; ///< Dimension depends on calibration
/// @name Standard Constructors
/// @{
@@ -54,12 +62,12 @@ public:
/** constructor with pose */
explicit PinholeCamera(const Pose3& pose) :
- pose_(pose) {
+ Base(pose) {
}
/** constructor with pose and calibration */
PinholeCamera(const Pose3& pose, const Calibration& K) :
- pose_(pose), K_(K) {
+ Base(pose), K_(K) {
}
/// @}
@@ -75,12 +83,7 @@ public:
*/
static PinholeCamera Level(const Calibration &K, const Pose2& pose2,
double height) {
- const double st = sin(pose2.theta()), ct = cos(pose2.theta());
- const Point3 x(st, -ct, 0), y(0, 0, -1), z(ct, st, 0);
- const Rot3 wRc(x, y, z);
- const Point3 t(pose2.x(), pose2.y(), height);
- const Pose3 pose3(wRc, t);
- return PinholeCamera(pose3, K);
+ return PinholeCamera(Base::LevelPose(pose2, height), K);
}
/// PinholeCamera::level with default calibration
@@ -99,28 +102,23 @@ public:
*/
static PinholeCamera Lookat(const Point3& eye, const Point3& target,
const Point3& upVector, const Calibration& K = Calibration()) {
- Point3 zc = target - eye;
- zc = zc / zc.norm();
- Point3 xc = (-upVector).cross(zc); // minus upVector since yc is pointing down
- xc = xc / xc.norm();
- Point3 yc = zc.cross(xc);
- Pose3 pose3(Rot3(xc, yc, zc), eye);
- return PinholeCamera(pose3, K);
+ return PinholeCamera(Base::LookatPose(eye, target, upVector), K);
}
/// @}
/// @name Advanced Constructors
/// @{
- explicit PinholeCamera(const Vector &v) {
- pose_ = Pose3::Expmap(v.head(6));
- if (v.size() > 6) {
- K_ = Calibration(v.tail(DimK));
- }
+ /// Init from vector, can be 6D (default calibration) or dim
+ explicit PinholeCamera(const Vector &v) :
+ Base(v.head<6>()) {
+ if (v.size() > 6)
+ K_ = Calibration(v.tail());
}
+ /// Init from Vector and calibration
PinholeCamera(const Vector &v, const Vector &K) :
- pose_(Pose3::Expmap(v)), K_(K) {
+ Base(v), K_(K) {
}
/// @}
@@ -128,14 +126,14 @@ public:
/// @{
/// assert equality up to a tolerance
- bool equals(const PinholeCamera &camera, double tol = 1e-9) const {
- return pose_.equals(camera.pose(), tol)
- && K_.equals(camera.calibration(), tol);
+ bool equals(const Base &camera, double tol = 1e-9) const {
+ const PinholeCamera* e = dynamic_cast(&camera);
+ return Base::equals(camera, tol) && K_.equals(e->calibration(), tol);
}
/// print
void print(const std::string& s = "PinholeCamera") const {
- pose_.print(s + ".pose");
+ Base::print(s);
K_.print(s + ".calibration");
}
@@ -147,31 +145,21 @@ public:
}
/// return pose
- inline Pose3& pose() {
- return pose_;
- }
-
- /// return pose, constant version
- inline const Pose3& pose() const {
- return pose_;
+ const Pose3& pose() const {
+ return Base::pose();
}
/// return pose, with derivative
- inline const Pose3& getPose(gtsam::OptionalJacobian<6, dimension> H) const {
+ const Pose3& getPose(OptionalJacobian<6, dimension> H) const {
if (H) {
H->setZero();
H->block(0, 0, 6, 6) = I_6x6;
}
- return pose_;
+ return Base::pose();
}
/// return calibration
- inline Calibration& calibration() {
- return K_;
- }
-
- /// return calibration
- inline const Calibration& calibration() const {
+ const Calibration& calibration() const {
return K_;
}
@@ -179,13 +167,13 @@ public:
/// @name Manifold
/// @{
- /// Manifold dimension
- inline size_t dim() const {
+ /// @deprecated
+ size_t dim() const {
return dimension;
}
- /// Manifold dimension
- inline static size_t Dim() {
+ /// @deprecated
+ static size_t Dim() {
return dimension;
}
@@ -194,9 +182,9 @@ public:
/// move a cameras according to d
PinholeCamera retract(const Vector& d) const {
if ((size_t) d.size() == 6)
- return PinholeCamera(pose().retract(d), calibration());
+ return PinholeCamera(this->pose().retract(d), calibration());
else
- return PinholeCamera(pose().retract(d.head(6)),
+ return PinholeCamera(this->pose().retract(d.head(6)),
calibration().retract(d.tail(calibration().dim())));
}
@@ -204,7 +192,7 @@ public:
VectorK6 localCoordinates(const PinholeCamera& T2) const {
VectorK6 d;
// TODO: why does d.head<6>() not compile??
- d.head(6) = pose().localCoordinates(T2.pose());
+ d.head(6) = this->pose().localCoordinates(T2.pose());
d.tail(DimK) = calibration().localCoordinates(T2.calibration());
return d;
}
@@ -218,32 +206,6 @@ public:
/// @name Transformations and measurement functions
/// @{
- /**
- * projects a 3-dimensional point in camera coordinates into the
- * camera and returns a 2-dimensional point, no calibration applied
- * @param P A point in camera coordinates
- * @param Dpoint is the 2*3 Jacobian w.r.t. P
- */
- static Point2 project_to_camera(const Point3& P, //
- OptionalJacobian<2, 3> Dpoint = boost::none) {
-#ifdef GTSAM_THROW_CHEIRALITY_EXCEPTION
- if (P.z() <= 0)
- throw CheiralityException();
-#endif
- double d = 1.0 / P.z();
- const double u = P.x() * d, v = P.y() * d;
- if (Dpoint)
- *Dpoint << d, 0.0, -u * d, 0.0, d, -v * d;
- return Point2(u, v);
- }
-
- /// Project a point into the image and check depth
- inline std::pair projectSafe(const Point3& pw) const {
- const Point3 pc = pose_.transform_to(pw);
- const Point2 pn = project_to_camera(pc);
- return std::make_pair(K_.uncalibrate(pn), pc.z() > 0);
- }
-
typedef Eigen::Matrix Matrix2K;
/** project a point from world coordinate to the image
@@ -252,31 +214,25 @@ public:
* @param Dpoint is the Jacobian w.r.t. point3
* @param Dcal is the Jacobian w.r.t. calibration
*/
- inline Point2 project(const Point3& pw, OptionalJacobian<2, 6> Dpose =
- boost::none, OptionalJacobian<2, 3> Dpoint = boost::none,
+ Point2 project(const Point3& pw, OptionalJacobian<2, 6> Dpose = boost::none,
+ OptionalJacobian<2, 3> Dpoint = boost::none,
OptionalJacobian<2, DimK> Dcal = boost::none) const {
- // Transform to camera coordinates and check cheirality
- const Point3 pc = pose_.transform_to(pw);
+ // project to normalized coordinates
+ const Point2 pn = PinholeBase::project2(pw, Dpose, Dpoint);
- // Project to normalized image coordinates
- const Point2 pn = project_to_camera(pc);
+ // uncalibrate to pixel coordinates
+ Matrix2 Dpi_pn;
+ const Point2 pi = calibration().uncalibrate(pn, Dcal,
+ Dpose || Dpoint ? &Dpi_pn : 0);
- if (Dpose || Dpoint) {
- const double z = pc.z(), d = 1.0 / z;
+ // If needed, apply chain rule
+ if (Dpose)
+ *Dpose = Dpi_pn * *Dpose;
+ if (Dpoint)
+ *Dpoint = Dpi_pn * *Dpoint;
- // uncalibration
- Matrix2 Dpi_pn;
- const Point2 pi = K_.uncalibrate(pn, Dcal, Dpi_pn);
-
- // chain the Jacobian matrices
- if (Dpose)
- calculateDpose(pn, d, Dpi_pn, *Dpose);
- if (Dpoint)
- calculateDpoint(pn, d, pose_.rotation().matrix(), Dpi_pn, *Dpoint);
- return pi;
- } else
- return K_.uncalibrate(pn, Dcal);
+ return pi;
}
/** project a point at infinity from world coordinate to the image
@@ -285,20 +241,19 @@ public:
* @param Dpoint is the Jacobian w.r.t. point3
* @param Dcal is the Jacobian w.r.t. calibration
*/
- inline Point2 projectPointAtInfinity(const Point3& pw,
- OptionalJacobian<2, 6> Dpose = boost::none,
- OptionalJacobian<2, 2> Dpoint = boost::none,
+ Point2 projectPointAtInfinity(const Point3& pw, OptionalJacobian<2, 6> Dpose =
+ boost::none, OptionalJacobian<2, 2> Dpoint = boost::none,
OptionalJacobian<2, DimK> Dcal = boost::none) const {
if (!Dpose && !Dpoint && !Dcal) {
- const Point3 pc = pose_.rotation().unrotate(pw); // get direction in camera frame (translation does not matter)
- const Point2 pn = project_to_camera(pc); // project the point to the camera
+ const Point3 pc = this->pose().rotation().unrotate(pw); // get direction in camera frame (translation does not matter)
+ const Point2 pn = Base::project_to_camera(pc); // project the point to the camera
return K_.uncalibrate(pn);
}
// world to camera coordinate
Matrix3 Dpc_rot, Dpc_point;
- const Point3 pc = pose_.rotation().unrotate(pw, Dpc_rot, Dpc_point);
+ const Point3 pc = this->pose().rotation().unrotate(pw, Dpc_rot, Dpc_point);
Matrix36 Dpc_pose;
Dpc_pose.setZero();
@@ -306,7 +261,7 @@ public:
// camera to normalized image coordinate
Matrix23 Dpn_pc; // 2*3
- const Point2 pn = project_to_camera(pc, Dpn_pc);
+ const Point2 pn = Base::project_to_camera(pc, Dpn_pc);
// uncalibration
Matrix2 Dpi_pn; // 2*2
@@ -323,65 +278,40 @@ public:
/** project a point from world coordinate to the image, fixed Jacobians
* @param pw is a point in the world coordinate
- * @param Dcamera is the Jacobian w.r.t. [pose3 calibration]
- * @param Dpoint is the Jacobian w.r.t. point3
*/
Point2 project2(
const Point3& pw, //
OptionalJacobian<2, dimension> Dcamera = boost::none,
OptionalJacobian<2, 3> Dpoint = boost::none) const {
- const Point3 pc = pose_.transform_to(pw);
- const Point2 pn = project_to_camera(pc);
+ // project to normalized coordinates
+ Matrix26 Dpose;
+ const Point2 pn = PinholeBase::project2(pw, Dpose, Dpoint);
- if (!Dcamera && !Dpoint) {
- return K_.uncalibrate(pn);
- } else {
- const double z = pc.z(), d = 1.0 / z;
+ // uncalibrate to pixel coordinates
+ Matrix2K Dcal;
+ Matrix2 Dpi_pn;
+ const Point2 pi = calibration().uncalibrate(pn, Dcamera ? &Dcal : 0,
+ Dcamera || Dpoint ? &Dpi_pn : 0);
- // uncalibration
- Matrix2K Dcal;
- Matrix2 Dpi_pn;
- const Point2 pi = K_.uncalibrate(pn, Dcal, Dpi_pn);
+ // If needed, calculate derivatives
+ if (Dcamera)
+ *Dcamera << Dpi_pn * Dpose, Dcal;
+ if (Dpoint)
+ *Dpoint = Dpi_pn * (*Dpoint);
- if (Dcamera) { // TODO why does leftCols<6>() not compile ??
- calculateDpose(pn, d, Dpi_pn, (*Dcamera).leftCols(6));
- (*Dcamera).rightCols(DimK) = Dcal; // Jacobian wrt calib
- }
- if (Dpoint) {
- calculateDpoint(pn, d, pose_.rotation().matrix(), Dpi_pn, *Dpoint);
- }
- return pi;
- }
- }
-
- /// backproject a 2-dimensional point to a 3-dimensional point at given depth
- inline Point3 backproject(const Point2& p, double depth) const {
- const Point2 pn = K_.calibrate(p);
- const Point3 pc(pn.x() * depth, pn.y() * depth, depth);
- return pose_.transform_from(pc);
- }
-
- /// backproject a 2-dimensional point to a 3-dimensional point at infinity
- inline Point3 backprojectPointAtInfinity(const Point2& p) const {
- const Point2 pn = K_.calibrate(p);
- const Point3 pc(pn.x(), pn.y(), 1.0); //by convention the last element is 1
- return pose_.rotation().rotate(pc);
+ return pi;
}
/**
* Calculate range to a landmark
* @param point 3D location of landmark
- * @param Dcamera the optionally computed Jacobian with respect to pose
- * @param Dpoint the optionally computed Jacobian with respect to the landmark
* @return range (double)
*/
- double range(
- const Point3& point, //
- OptionalJacobian<1, dimension> Dcamera = boost::none,
- OptionalJacobian<1, 3> Dpoint = boost::none) const {
+ double range(const Point3& point, OptionalJacobian<1, dimension> Dcamera =
+ boost::none, OptionalJacobian<1, 3> Dpoint = boost::none) const {
Matrix16 Dpose_;
- double result = pose_.range(point, Dcamera ? &Dpose_ : 0, Dpoint);
+ double result = this->pose().range(point, Dcamera ? &Dpose_ : 0, Dpoint);
if (Dcamera)
*Dcamera << Dpose_, Eigen::Matrix::Zero();
return result;
@@ -390,16 +320,12 @@ public:
/**
* Calculate range to another pose
* @param pose Other SO(3) pose
- * @param Dcamera the optionally computed Jacobian with respect to pose
- * @param Dpose2 the optionally computed Jacobian with respect to the other pose
* @return range (double)
*/
- double range(
- const Pose3& pose, //
- OptionalJacobian<1, dimension> Dcamera = boost::none,
- OptionalJacobian<1, 6> Dpose = boost::none) const {
+ double range(const Pose3& pose, OptionalJacobian<1, dimension> Dcamera =
+ boost::none, OptionalJacobian<1, 6> Dpose = boost::none) const {
Matrix16 Dpose_;
- double result = pose_.range(pose, Dcamera ? &Dpose_ : 0, Dpose);
+ double result = this->pose().range(pose, Dcamera ? &Dpose_ : 0, Dpose);
if (Dcamera)
*Dcamera << Dpose_, Eigen::Matrix::Zero();
return result;
@@ -408,26 +334,21 @@ public:
/**
* Calculate range to another camera
* @param camera Other camera
- * @param Dcamera the optionally computed Jacobian with respect to pose
- * @param Dother the optionally computed Jacobian with respect to the other camera
* @return range (double)
*/
template
- double range(
- const PinholeCamera& camera, //
+ double range(const PinholeCamera& camera,
OptionalJacobian<1, dimension> Dcamera = boost::none,
-// OptionalJacobian<1, 6 + traits::dimension::value> Dother =
- boost::optional Dother =
- boost::none) const {
+ boost::optional Dother = boost::none) const {
Matrix16 Dcamera_, Dother_;
- double result = pose_.range(camera.pose(), Dcamera ? &Dcamera_ : 0,
+ double result = this->pose().range(camera.pose(), Dcamera ? &Dcamera_ : 0,
Dother ? &Dother_ : 0);
if (Dcamera) {
- Dcamera->resize(1, 6 + DimK);
+ Dcamera->resize(1, 6 + DimK);
*Dcamera << Dcamera_, Eigen::Matrix::Zero();
}
if (Dother) {
- Dother->resize(1, 6+CalibrationB::dimension);
+ Dother->resize(1, 6 + CalibrationB::dimension);
Dother->setZero();
Dother->block(0, 0, 1, 6) = Dother_;
}
@@ -437,12 +358,9 @@ public:
/**
* Calculate range to another camera
* @param camera Other camera
- * @param Dcamera the optionally computed Jacobian with respect to pose
- * @param Dother the optionally computed Jacobian with respect to the other camera
* @return range (double)
*/
- double range(
- const CalibratedCamera& camera, //
+ double range(const CalibratedCamera& camera,
OptionalJacobian<1, dimension> Dcamera = boost::none,
OptionalJacobian<1, 6> Dother = boost::none) const {
return range(camera.pose(), Dcamera, Dother);
@@ -450,65 +368,26 @@ public:
private:
- /**
- * Calculate Jacobian with respect to pose
- * @param pn projection in normalized coordinates
- * @param d disparity (inverse depth)
- * @param Dpi_pn derivative of uncalibrate with respect to pn
- * @param Dpose Output argument, can be matrix or block, assumed right size !
- * See http://eigen.tuxfamily.org/dox/TopicFunctionTakingEigenTypes.html
- */
- template
- static void calculateDpose(const Point2& pn, double d, const Matrix2& Dpi_pn,
- Eigen::MatrixBase const & Dpose) {
- // optimized version of derivatives, see CalibratedCamera.nb
- const double u = pn.x(), v = pn.y();
- double uv = u * v, uu = u * u, vv = v * v;
- Matrix26 Dpn_pose;
- Dpn_pose << uv, -1 - uu, v, -d, 0, d * u, 1 + vv, -uv, -u, 0, -d, d * v;
- assert(Dpose.rows()==2 && Dpose.cols()==6);
- const_cast&>(Dpose) = //
- Dpi_pn * Dpn_pose;
- }
-
- /**
- * Calculate Jacobian with respect to point
- * @param pn projection in normalized coordinates
- * @param d disparity (inverse depth)
- * @param Dpi_pn derivative of uncalibrate with respect to pn
- * @param Dpoint Output argument, can be matrix or block, assumed right size !
- * See http://eigen.tuxfamily.org/dox/TopicFunctionTakingEigenTypes.html
- */
- template
- static void calculateDpoint(const Point2& pn, double d, const Matrix3& R,
- const Matrix2& Dpi_pn, Eigen::MatrixBase const & Dpoint) {
- // optimized version of derivatives, see CalibratedCamera.nb
- const double u = pn.x(), v = pn.y();
- Matrix23 Dpn_point;
- Dpn_point << //
- R(0, 0) - u * R(0, 2), R(1, 0) - u * R(1, 2), R(2, 0) - u * R(2, 2), //
- /**/R(0, 1) - v * R(0, 2), R(1, 1) - v * R(1, 2), R(2, 1) - v * R(2, 2);
- Dpn_point *= d;
- assert(Dpoint.rows()==2 && Dpoint.cols()==3);
- const_cast&>(Dpoint) = //
- Dpi_pn * Dpn_point;
- }
-
/** Serialization function */
friend class boost::serialization::access;
template
void serialize(Archive & ar, const unsigned int version) {
- ar & BOOST_SERIALIZATION_NVP(pose_);
+ ar
+ & boost::serialization::make_nvp("PinholeBaseK",
+ boost::serialization::base_object(*this));
ar & BOOST_SERIALIZATION_NVP(K_);
}
};
+template
+struct traits > : public internal::Manifold<
+ PinholeCamera > {
+};
template
-struct traits< PinholeCamera > : public internal::Manifold > {};
-
-template
-struct traits< const PinholeCamera > : public internal::Manifold > {};
+struct traits > : public internal::Manifold<
+ PinholeCamera > {
+};
} // \ gtsam
diff --git a/gtsam/geometry/PinholePose.h b/gtsam/geometry/PinholePose.h
new file mode 100644
index 000000000..7588f517e
--- /dev/null
+++ b/gtsam/geometry/PinholePose.h
@@ -0,0 +1,344 @@
+/* ----------------------------------------------------------------------------
+
+ * 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 PinholePose.h
+ * @brief Pinhole camera with known calibration
+ * @author Yong-Dian Jian
+ * @author Frank Dellaert
+ * @date Feb 20, 2015
+ */
+
+#pragma once
+
+#include
+#include
+#include
+
+namespace gtsam {
+
+/**
+ * A pinhole camera class that has a Pose3 and a *fixed* Calibration.
+ * @addtogroup geometry
+ * \nosubgrouping
+ */
+template
+class GTSAM_EXPORT PinholeBaseK: public PinholeBase {
+
+ GTSAM_CONCEPT_MANIFOLD_TYPE(Calibration)
+
+public :
+
+ /// @name Standard Constructors
+ /// @{
+
+ /** default constructor */
+ PinholeBaseK() {
+ }
+
+ /** constructor with pose */
+ explicit PinholeBaseK(const Pose3& pose) :
+ PinholeBase(pose) {
+ }
+
+ /// @}
+ /// @name Advanced Constructors
+ /// @{
+
+ explicit PinholeBaseK(const Vector &v) :
+ PinholeBase(v) {
+ }
+
+ /// @}
+ /// @name Standard Interface
+ /// @{
+
+ virtual ~PinholeBaseK() {
+ }
+
+ /// return calibration
+ virtual const Calibration& calibration() const = 0;
+
+ /// @}
+ /// @name Transformations and measurement functions
+ /// @{
+
+ /// Project a point into the image and check depth
+ std::pair projectSafe(const Point3& pw) const {
+ std::pair pn = PinholeBase::projectSafe(pw);
+ pn.first = calibration().uncalibrate(pn.first);
+ return pn;
+ }
+
+ /** project a point from world coordinate to the image, fixed Jacobians
+ * @param pw is a point in the world coordinates
+ */
+ Point2 project2(const Point3& pw, OptionalJacobian<2, 6> Dpose = boost::none,
+ OptionalJacobian<2, 3> Dpoint = boost::none) const {
+
+ // project to normalized coordinates
+ const Point2 pn = PinholeBase::project2(pw, Dpose, Dpoint);
+
+ // uncalibrate to pixel coordinates
+ Matrix2 Dpi_pn;
+ const Point2 pi = calibration().uncalibrate(pn, boost::none,
+ Dpose || Dpoint ? &Dpi_pn : 0);
+
+ // If needed, apply chain rule
+ if (Dpose) *Dpose = Dpi_pn * (*Dpose);
+ if (Dpoint) *Dpoint = Dpi_pn * (*Dpoint);
+
+ return pi;
+ }
+
+ /// backproject a 2-dimensional point to a 3-dimensional point at given depth
+ Point3 backproject(const Point2& p, double depth) const {
+ const Point2 pn = calibration().calibrate(p);
+ return pose().transform_from(backproject_from_camera(pn, depth));
+ }
+
+ /// backproject a 2-dimensional point to a 3-dimensional point at infinity
+ Point3 backprojectPointAtInfinity(const Point2& p) const {
+ const Point2 pn = calibration().calibrate(p);
+ const Point3 pc(pn.x(), pn.y(), 1.0); //by convention the last element is 1
+ return pose().rotation().rotate(pc);
+ }
+
+ /**
+ * Calculate range to a landmark
+ * @param point 3D location of landmark
+ * @return range (double)
+ */
+ double range(const Point3& point,
+ OptionalJacobian<1, 6> Dcamera = boost::none,
+ OptionalJacobian<1, 3> Dpoint = boost::none) const {
+ return pose().range(point, Dcamera, Dpoint);
+ }
+
+ /**
+ * Calculate range to another pose
+ * @param pose Other SO(3) pose
+ * @return range (double)
+ */
+ double range(const Pose3& pose, OptionalJacobian<1, 6> Dcamera = boost::none,
+ OptionalJacobian<1, 6> Dpose = boost::none) const {
+ return this->pose().range(pose, Dcamera, Dpose);
+ }
+
+ /**
+ * Calculate range to a CalibratedCamera
+ * @param camera Other camera
+ * @return range (double)
+ */
+ double range(const CalibratedCamera& camera, OptionalJacobian<1, 6> Dcamera =
+ boost::none, OptionalJacobian<1, 6> Dother = boost::none) const {
+ return pose().range(camera.pose(), Dcamera, Dother);
+ }
+
+ /**
+ * Calculate range to a PinholePoseK derived class
+ * @param camera Other camera
+ * @return range (double)
+ */
+ template
+ double range(const PinholeBaseK& camera,
+ OptionalJacobian<1, 6> Dcamera = boost::none,
+ OptionalJacobian<1, 6> Dother = boost::none) const {
+ return pose().range(camera.pose(), Dcamera, Dother);
+ }
+
+private:
+
+ /** Serialization function */
+ friend class boost::serialization::access;
+ template
+ void serialize(Archive & ar, const unsigned int version) {
+ ar
+ & boost::serialization::make_nvp("PinholeBase",
+ boost::serialization::base_object(*this));
+ }
+
+};
+// end of class PinholeBaseK
+
+/**
+ * A pinhole camera class that has a Pose3 and a *fixed* Calibration.
+ * Instead of using this class, one might consider calibrating the measurements
+ * and using CalibratedCamera, which would then be faster.
+ * @addtogroup geometry
+ * \nosubgrouping
+ */
+template
+class GTSAM_EXPORT PinholePose: public PinholeBaseK {
+
+private:
+
+ typedef PinholeBaseK Base; ///< base class has 3D pose as private member
+ boost::shared_ptr K_; ///< shared pointer to fixed calibration
+
+public:
+
+ enum {
+ dimension = 6
+ }; ///< There are 6 DOF to optimize for
+
+ /// @name Standard Constructors
+ /// @{
+
+ /** default constructor */
+ PinholePose() {
+ }
+
+ /** constructor with pose, uses default calibration */
+ explicit PinholePose(const Pose3& pose) :
+ Base(pose), K_(new Calibration()) {
+ }
+
+ /** constructor with pose and calibration */
+ PinholePose(const Pose3& pose, const boost::shared_ptr& K) :
+ Base(pose), K_(K) {
+ }
+
+ /// @}
+ /// @name Named Constructors
+ /// @{
+
+ /**
+ * Create a level camera at the given 2D pose and height
+ * @param K the calibration
+ * @param pose2 specifies the location and viewing direction
+ * (theta 0 = looking in direction of positive X axis)
+ * @param height camera height
+ */
+ static PinholePose Level(const boost::shared_ptr& K,
+ const Pose2& pose2, double height) {
+ return PinholePose(Base::LevelPose(pose2, height), K);
+ }
+
+ /// PinholePose::level with default calibration
+ static PinholePose Level(const Pose2& pose2, double height) {
+ return PinholePose::Level(boost::make_shared(), pose2, height);
+ }
+
+ /**
+ * Create a camera at the given eye position looking at a target point in the scene
+ * with the specified up direction vector.
+ * @param eye specifies the camera position
+ * @param target the point to look at
+ * @param upVector specifies the camera up direction vector,
+ * doesn't need to be on the image plane nor orthogonal to the viewing axis
+ * @param K optional calibration parameter
+ */
+ static PinholePose Lookat(const Point3& eye, const Point3& target,
+ const Point3& upVector, const boost::shared_ptr& K =
+ boost::make_shared()) {
+ return PinholePose(Base::LookatPose(eye, target, upVector), K);
+ }
+
+ /// @}
+ /// @name Advanced Constructors
+ /// @{
+
+ /// Init from 6D vector
+ explicit PinholePose(const Vector &v) :
+ Base(v), K_(new Calibration()) {
+ }
+
+ /// Init from Vector and calibration
+ PinholePose(const Vector &v, const Vector &K) :
+ Base(v), K_(new Calibration(K)) {
+ }
+
+ /// @}
+ /// @name Testable
+ /// @{
+
+ /// assert equality up to a tolerance
+ bool equals(const Base &camera, double tol = 1e-9) const {
+ const PinholePose* e = dynamic_cast(&camera);
+ return Base::equals(camera, tol) && K_->equals(e->calibration(), tol);
+ }
+
+ /// print
+ void print(const std::string& s = "PinholePose") const {
+ Base::print(s);
+ K_->print(s + ".calibration");
+ }
+
+ /// @}
+ /// @name Standard Interface
+ /// @{
+
+ virtual ~PinholePose() {
+ }
+
+ /// return calibration
+ virtual const Calibration& calibration() const {
+ return *K_;
+ }
+
+ /// @}
+ /// @name Manifold
+ /// @{
+
+ /// @deprecated
+ size_t dim() const {
+ return 6;
+ }
+
+ /// @deprecated
+ static size_t Dim() {
+ return 6;
+ }
+
+ /// move a cameras according to d
+ PinholePose retract(const Vector6& d) const {
+ return PinholePose(Base::pose().retract(d), K_);
+ }
+
+ /// return canonical coordinate
+ Vector6 localCoordinates(const PinholePose& p) const {
+ return Base::pose().localCoordinates(p.Base::pose());
+ }
+
+ /// for Canonical
+ static PinholePose identity() {
+ return PinholePose(); // assumes that the default constructor is valid
+ }
+
+ /// @}
+
+private:
+
+ /** Serialization function */
+ friend class boost::serialization::access;
+ template
+ void serialize(Archive & ar, const unsigned int version) {
+ ar
+ & boost::serialization::make_nvp("PinholeBaseK",
+ boost::serialization::base_object(*this));
+ ar & BOOST_SERIALIZATION_NVP(K_);
+ }
+
+};
+// end of class PinholePose
+
+template
+struct traits > : public internal::Manifold<
+ PinholePose > {
+};
+
+template
+struct traits > : public internal::Manifold<
+ PinholePose > {
+};
+
+} // \ gtsam
diff --git a/gtsam/geometry/StereoCamera.cpp b/gtsam/geometry/StereoCamera.cpp
index 9170f8282..9e5b88b31 100644
--- a/gtsam/geometry/StereoCamera.cpp
+++ b/gtsam/geometry/StereoCamera.cpp
@@ -29,16 +29,15 @@ namespace gtsam {
}
/* ************************************************************************* */
- StereoPoint2 StereoCamera::project(const Point3& point,
- OptionalJacobian<3,6> H1, OptionalJacobian<3,3> H2,
- OptionalJacobian<3,6> H3) const {
+ StereoPoint2 StereoCamera::project(const Point3& point) const {
+ return project2(point);
+ }
+
+ /* ************************************************************************* */
+ StereoPoint2 StereoCamera::project2(const Point3& point,
+ OptionalJacobian<3,6> H1, OptionalJacobian<3,3> H2) const {
-#ifdef STEREOCAMERA_CHAIN_RULE
- const Point3 q = leftCamPose_.transform_to(point, H1, H2);
-#else
- // omit derivatives
const Point3 q = leftCamPose_.transform_to(point);
-#endif
if ( q.z() <= 0 ) throw StereoCheiralityException();
@@ -56,12 +55,6 @@ namespace gtsam {
// check if derivatives need to be computed
if (H1 || H2) {
-#ifdef STEREOCAMERA_CHAIN_RULE
- // just implement chain rule
- Matrix3 D_project_point = Dproject_to_stereo_camera1(q); // 3x3 Jacobian
- if (H1) *H1 = D_project_point*(*H1);
- if (H2) *H2 = D_project_point*(*H2);
-#else
// optimized version, see StereoCamera.nb
if (H1) {
const double v1 = v/fy, v2 = fx*v1, dx=d*x;
@@ -76,10 +69,6 @@ namespace gtsam {
fy*R(0, 1) - R(0, 2)*v , fy*R(1, 1) - R(1, 2)*v , fy*R(2, 1) - R(2, 2)*v;
*H2 << d * (*H2);
}
-#endif
- if (H3)
- // TODO, this is set to zero, as Cal3_S2Stereo cannot be optimized yet
- H3->setZero();
}
// finally translate
@@ -87,15 +76,23 @@ namespace gtsam {
}
/* ************************************************************************* */
- Matrix3 StereoCamera::Dproject_to_stereo_camera1(const Point3& P) const {
- double d = 1.0 / P.z(), d2 = d*d;
- const Cal3_S2Stereo& K = *K_;
- double f_x = K.fx(), f_y = K.fy(), b = K.baseline();
- Matrix3 m;
- m << f_x*d, 0.0, -d2*f_x* P.x(),
- f_x*d, 0.0, -d2*f_x*(P.x() - b),
- 0.0, f_y*d, -d2*f_y* P.y();
- return m;
+ StereoPoint2 StereoCamera::project(const Point3& point,
+ OptionalJacobian<3,6> H1, OptionalJacobian<3,3> H2,
+ OptionalJacobian<3,0> H3) const {
+ if (H3)
+ throw std::runtime_error(
+ "StereoCamera::project does not support third derivative - BTW use project2");
+ return project2(point,H1,H2);
+ }
+
+ /* ************************************************************************* */
+ Point3 StereoCamera::backproject(const StereoPoint2& z) const {
+ Vector measured = z.vector();
+ double Z = K_->baseline() * K_->fx() / (measured[0] - measured[1]);
+ double X = Z * (measured[0] - K_->px()) / K_->fx();
+ double Y = Z * (measured[2] - K_->py()) / K_->fy();
+ Point3 world_point = leftCamPose_.transform_from(Point3(X, Y, Z));
+ return world_point;
}
}
diff --git a/gtsam/geometry/StereoCamera.h b/gtsam/geometry/StereoCamera.h
index 913b1eab3..ea28ecfc7 100644
--- a/gtsam/geometry/StereoCamera.h
+++ b/gtsam/geometry/StereoCamera.h
@@ -17,9 +17,6 @@
#pragma once
-#include
-
-#include
#include
#include
#include
@@ -28,32 +25,47 @@ namespace gtsam {
class GTSAM_EXPORT StereoCheiralityException: public std::runtime_error {
public:
- StereoCheiralityException() : std::runtime_error("Stereo Cheirality Exception") {}
+ StereoCheiralityException() :
+ std::runtime_error("Stereo Cheirality Exception") {
+ }
};
-
/**
* A stereo camera class, parameterize by left camera pose and stereo calibration
* @addtogroup geometry
*/
class GTSAM_EXPORT StereoCamera {
+public:
+
+ /**
+ * Some classes template on either PinholeCamera or StereoCamera,
+ * and this typedef informs those classes what "project" returns.
+ */
+ typedef StereoPoint2 Measurement;
+
private:
Pose3 leftCamPose_;
Cal3_S2Stereo::shared_ptr K_;
public:
- enum { dimension = 6 };
+ enum {
+ dimension = 6
+ };
/// @name Standard Constructors
/// @{
- StereoCamera() {
+ /// Default constructor allocates a calibration!
+ StereoCamera() :
+ K_(new Cal3_S2Stereo()) {
}
+ /// Construct from pose and shared calibration
StereoCamera(const Pose3& leftCamPose, const Cal3_S2Stereo::shared_ptr K);
+ /// Return shared pointer to calibration
const Cal3_S2Stereo::shared_ptr calibration() const {
return K_;
}
@@ -62,26 +74,28 @@ public:
/// @name Testable
/// @{
+ /// print
void print(const std::string& s = "") const {
leftCamPose_.print(s + ".camera.");
K_->print(s + ".calibration.");
}
+ /// equals
bool equals(const StereoCamera &camera, double tol = 1e-9) const {
- return leftCamPose_.equals(camera.leftCamPose_, tol) && K_->equals(
- *camera.K_, tol);
+ return leftCamPose_.equals(camera.leftCamPose_, tol)
+ && K_->equals(*camera.K_, tol);
}
/// @}
/// @name Manifold
/// @{
- /** Dimensionality of the tangent space */
+ /// Dimensionality of the tangent space
inline size_t dim() const {
return 6;
}
- /** Dimensionality of the tangent space */
+ /// Dimensionality of the tangent space
static inline size_t Dim() {
return 6;
}
@@ -100,42 +114,46 @@ public:
/// @name Standard Interface
/// @{
+ /// pose
const Pose3& pose() const {
return leftCamPose_;
}
+ /// baseline
double baseline() const {
return K_->baseline();
}
- /*
- * project 3D point and compute optional derivatives
+ /// Project 3D point to StereoPoint2 (uL,uR,v)
+ StereoPoint2 project(const Point3& point) const;
+
+ /** Project 3D point and compute optional derivatives
+ * @param H1 derivative with respect to pose
+ * @param H2 derivative with respect to point
+ */
+ StereoPoint2 project2(const Point3& point, OptionalJacobian<3, 6> H1 =
+ boost::none, OptionalJacobian<3, 3> H2 = boost::none) const;
+
+ /// back-project a measurement
+ Point3 backproject(const StereoPoint2& z) const;
+
+ /// @}
+ /// @name Deprecated
+ /// @{
+
+ /** Project 3D point and compute optional derivatives
+ * @deprecated, use project2 - this class has fixed calibration
* @param H1 derivative with respect to pose
* @param H2 derivative with respect to point
* @param H3 IGNORED (for calibration)
*/
- StereoPoint2 project(const Point3& point,
- OptionalJacobian<3, 6> H1 = boost::none,
- OptionalJacobian<3, 3> H2 = boost::none,
- OptionalJacobian<3, 6> H3 = boost::none) const;
-
- /**
- *
- */
- Point3 backproject(const StereoPoint2& z) const {
- Vector measured = z.vector();
- double Z = K_->baseline()*K_->fx()/(measured[0]-measured[1]);
- double X = Z *(measured[0]- K_->px()) / K_->fx();
- double Y = Z *(measured[2]- K_->py()) / K_->fy();
- Point3 world_point = leftCamPose_.transform_from(Point3(X, Y, Z));
- return world_point;
- }
+ StereoPoint2 project(const Point3& point, OptionalJacobian<3, 6> H1,
+ OptionalJacobian<3, 3> H2 = boost::none, OptionalJacobian<3, 0> H3 =
+ boost::none) const;
/// @}
private:
- /** utility functions */
- Matrix3 Dproject_to_stereo_camera1(const Point3& P) const;
friend class boost::serialization::access;
template
@@ -147,8 +165,10 @@ private:
};
template<>
-struct traits : public internal::Manifold {};
+struct traits : public internal::Manifold {
+};
template<>
-struct traits : public internal::Manifold {};
+struct traits : public internal::Manifold {
+};
}
diff --git a/gtsam/geometry/tests/testCalibratedCamera.cpp b/gtsam/geometry/tests/testCalibratedCamera.cpp
index 6a990e08e..b1e265266 100644
--- a/gtsam/geometry/tests/testCalibratedCamera.cpp
+++ b/gtsam/geometry/tests/testCalibratedCamera.cpp
@@ -29,6 +29,7 @@ using namespace gtsam;
GTSAM_CONCEPT_MANIFOLD_INST(CalibratedCamera)
+// Camera situated at 0.5 meters high, looking down
static const Pose3 pose1((Matrix)(Matrix(3,3) <<
1., 0., 0.,
0.,-1., 0.,
@@ -97,24 +98,37 @@ TEST( CalibratedCamera, Dproject_to_camera1) {
}
/* ************************************************************************* */
-static Point2 project2(const Pose3& pose, const Point3& point) {
- return CalibratedCamera(pose).project(point);
+static Point2 project2(const CalibratedCamera& camera, const Point3& point) {
+ return camera.project(point);
}
TEST( CalibratedCamera, Dproject_point_pose)
{
Matrix Dpose, Dpoint;
Point2 result = camera.project(point1, Dpose, Dpoint);
- Matrix numerical_pose = numericalDerivative21(project2, pose1, point1);
- Matrix numerical_point = numericalDerivative22(project2, pose1, point1);
+ Matrix numerical_pose = numericalDerivative21(project2, camera, point1);
+ Matrix numerical_point = numericalDerivative22(project2, camera, point1);
CHECK(assert_equal(Point3(-0.08, 0.08, 0.5), camera.pose().transform_to(point1)));
CHECK(assert_equal(Point2(-.16, .16), result));
CHECK(assert_equal(numerical_pose, Dpose, 1e-7));
CHECK(assert_equal(numerical_point, Dpoint, 1e-7));
}
+/* ************************************************************************* */
+// Add a test with more arbitrary rotation
+TEST( CalibratedCamera, Dproject_point_pose2)
+{
+ static const Pose3 pose1(Rot3::ypr(0.1, -0.1, 0.4), Point3(0, 0, -10));
+ static const CalibratedCamera camera(pose1);
+ Matrix Dpose, Dpoint;
+ camera.project(point1, Dpose, Dpoint);
+ Matrix numerical_pose = numericalDerivative21(project2, camera, point1);
+ Matrix numerical_point = numericalDerivative22(project2, camera, point1);
+ CHECK(assert_equal(numerical_pose, Dpose, 1e-7));
+ CHECK(assert_equal(numerical_point, Dpoint, 1e-7));
+}
+
/* ************************************************************************* */
int main() { TestResult tr; return TestRegistry::runAllTests(tr); }
/* ************************************************************************* */
-
diff --git a/gtsam/geometry/tests/testCameraSet.cpp b/gtsam/geometry/tests/testCameraSet.cpp
new file mode 100644
index 000000000..42cf0f299
--- /dev/null
+++ b/gtsam/geometry/tests/testCameraSet.cpp
@@ -0,0 +1,114 @@
+/* ----------------------------------------------------------------------------
+
+ * 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 testCameraSet.cpp
+ * @brief Unit tests for testCameraSet Class
+ * @author Frank Dellaert
+ * @date Feb 19, 2015
+ */
+
+#include
+#include
+#include
+#include
+#include
+
+using namespace std;
+using namespace gtsam;
+
+/* ************************************************************************* */
+// Cal3Bundler test
+#include
+#include
+TEST(CameraSet, Pinhole) {
+ typedef PinholeCamera Camera;
+ typedef vector ZZ;
+ CameraSet set;
+ Camera camera;
+ set.push_back(camera);
+ set.push_back(camera);
+ Point3 p(0, 0, 1);
+ CHECK(assert_equal(set, set));
+ CameraSet set2 = set;
+ set2.push_back(camera);
+ CHECK(!set.equals(set2));
+
+ // Check measurements
+ Point2 expected;
+ ZZ z = set.project(p);
+ CHECK(assert_equal(expected, z[0]));
+ CHECK(assert_equal(expected, z[1]));
+
+ // Calculate expected derivatives using Pinhole
+ Matrix46 actualF;
+ Matrix43 actualE;
+ Matrix43 actualH;
+ {
+ Matrix26 F1;
+ Matrix23 E1;
+ Matrix23 H1;
+ camera.project(p, F1, E1, H1);
+ actualE << E1, E1;
+ actualF << F1, F1;
+ actualH << H1, H1;
+ }
+
+ // Check computed derivatives
+ Matrix F, E, H;
+ set.project(p, F, E, H);
+ CHECK(assert_equal(actualF, F));
+ CHECK(assert_equal(actualE, E));
+ CHECK(assert_equal(actualH, H));
+}
+
+/* ************************************************************************* */
+#include
+TEST(CameraSet, Stereo) {
+ typedef vector ZZ;
+ CameraSet set;
+ StereoCamera camera;
+ set.push_back(camera);
+ set.push_back(camera);
+ Point3 p(0, 0, 1);
+ EXPECT_LONGS_EQUAL(6, traits::dimension);
+
+ // Check measurements
+ StereoPoint2 expected(0, -1, 0);
+ ZZ z = set.project(p);
+ CHECK(assert_equal(expected, z[0]));
+ CHECK(assert_equal(expected, z[1]));
+
+ // Calculate expected derivatives using Pinhole
+ Matrix66 actualF;
+ Matrix63 actualE;
+ {
+ Matrix36 F1;
+ Matrix33 E1;
+ camera.project(p, F1, E1);
+ actualE << E1, E1;
+ actualF << F1, F1;
+ }
+
+ // Check computed derivatives
+ Matrix F, E;
+ set.project(p, F, E);
+ CHECK(assert_equal(actualF, F));
+ CHECK(assert_equal(actualE, E));
+}
+
+/* ************************************************************************* */
+int main() {
+ TestResult tr;
+ return TestRegistry::runAllTests(tr);
+}
+/* ************************************************************************* */
+
diff --git a/gtsam/geometry/tests/testPinholeCamera.cpp b/gtsam/geometry/tests/testPinholeCamera.cpp
index 20f7a3231..0e610d8d6 100644
--- a/gtsam/geometry/tests/testPinholeCamera.cpp
+++ b/gtsam/geometry/tests/testPinholeCamera.cpp
@@ -15,12 +15,14 @@
* @brief test PinholeCamera class
*/
-#include
-#include
-#include