diff --git a/.cproject b/.cproject
index ac9b166ec..5d8469baa 100644
--- a/.cproject
+++ b/.cproject
@@ -1309,6 +1309,7 @@
make
+
testSimulated2DOriented.run
true
false
@@ -1348,6 +1349,7 @@
make
+
testSimulated2D.run
true
false
@@ -1355,6 +1357,7 @@
make
+
testSimulated3D.run
true
false
@@ -1458,7 +1461,6 @@
make
-
testErrors.run
true
false
@@ -1769,7 +1771,6 @@
cpack
-
-G DEB
true
false
@@ -1777,7 +1778,6 @@
cpack
-
-G RPM
true
false
@@ -1785,7 +1785,6 @@
cpack
-
-G TGZ
true
false
@@ -1793,7 +1792,6 @@
cpack
-
--config CPackSourceConfig.cmake
true
false
@@ -1985,6 +1983,7 @@
make
+
tests/testGaussianISAM2
true
false
@@ -2120,7 +2119,6 @@
make
-
tests/testBayesTree.run
true
false
@@ -2128,7 +2126,6 @@
make
-
testBinaryBayesNet.run
true
false
@@ -2176,7 +2173,6 @@
make
-
testSymbolicBayesNet.run
true
false
@@ -2184,7 +2180,6 @@
make
-
tests/testSymbolicFactor.run
true
false
@@ -2192,7 +2187,6 @@
make
-
testSymbolicFactorGraph.run
true
false
@@ -2208,7 +2202,6 @@
make
-
tests/testBayesTree
true
false
@@ -2902,6 +2895,14 @@
true
true
+
+ make
+ -j4
+ timeSchurFactors.run
+ true
+ true
+ true
+
make
-j5
@@ -3344,7 +3345,6 @@
make
-
testGraph.run
true
false
@@ -3352,7 +3352,6 @@
make
-
testJunctionTree.run
true
false
@@ -3360,7 +3359,6 @@
make
-
testSymbolicBayesNetB.run
true
false
diff --git a/CMakeLists.txt b/CMakeLists.txt
index 6e9aa0009..fd11a6733 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -158,6 +158,12 @@ else()
set(GTSAM_USE_TBB 0) # This will go into config.h
endif()
+###############################################################################
+# Prohibit Timing build mode in combination with TBB
+if(GTSAM_USE_TBB AND (CMAKE_BUILD_TYPE STREQUAL "Timing"))
+ message(FATAL_ERROR "Timing build mode cannot be used together with TBB. Use a sampling profiler such as Instruments or Intel VTune Amplifier instead.")
+endif()
+
###############################################################################
# Find Google perftools
@@ -173,6 +179,11 @@ if(MKL_FOUND AND GTSAM_WITH_EIGEN_MKL)
set(EIGEN_USE_MKL_ALL 1) # This will go into config.h - it makes Eigen use MKL
include_directories(${MKL_INCLUDE_DIR})
list(APPEND GTSAM_ADDITIONAL_LIBRARIES ${MKL_LIBRARIES})
+
+ # --no-as-needed is required with gcc according to the MKL link advisor
+ if(CMAKE_CXX_COMPILER_ID STREQUAL "GNU")
+ set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} -Wl,--no-as-needed")
+ endif()
else()
set(GTSAM_USE_EIGEN_MKL 0)
set(EIGEN_USE_MKL_ALL 0)
diff --git a/cmake/GtsamTesting.cmake b/cmake/GtsamTesting.cmake
index 4b3af9810..3e5cadd32 100644
--- a/cmake/GtsamTesting.cmake
+++ b/cmake/GtsamTesting.cmake
@@ -195,7 +195,9 @@ macro(gtsamAddTestsGlob_impl groupName globPatterns excludedFiles linkLibraries)
add_test(NAME ${target_name} COMMAND ${target_name})
add_dependencies(check.${groupName} ${target_name})
add_dependencies(check ${target_name})
- add_dependencies(all.tests ${script_name})
+ if(NOT XCODE_VERSION)
+ add_dependencies(all.tests ${script_name})
+ endif()
# Add TOPSRCDIR
set_property(SOURCE ${script_srcs} APPEND PROPERTY COMPILE_DEFINITIONS "TOPSRCDIR=\"${PROJECT_SOURCE_DIR}\"")
diff --git a/examples/Data/.gitignore b/examples/Data/.gitignore
new file mode 100644
index 000000000..2211df63d
--- /dev/null
+++ b/examples/Data/.gitignore
@@ -0,0 +1 @@
+*.txt
diff --git a/examples/SFMExample.cpp b/examples/SFMExample.cpp
index 38dd1ca81..8da9847b8 100644
--- a/examples/SFMExample.cpp
+++ b/examples/SFMExample.cpp
@@ -97,7 +97,7 @@ int main(int argc, char* argv[]) {
// Intentionally initialize the variables off from the ground truth
Values initialEstimate;
for (size_t i = 0; i < poses.size(); ++i)
- initialEstimate.insert(Symbol('x', i), poses[i].compose(Pose3(Rot3::rodriguez(-0.1, 0.2, 0.25), Point3(0.05, -0.10, 0.20))));
+ initialEstimate.insert(Symbol('x', i), poses[i].compose(Pose3(Rot3::Rodrigues(-0.1, 0.2, 0.25), Point3(0.05, -0.10, 0.20))));
for (size_t j = 0; j < points.size(); ++j)
initialEstimate.insert(Symbol('l', j), points[j].compose(Point3(-0.25, 0.20, 0.15)));
initialEstimate.print("Initial Estimates:\n");
diff --git a/examples/SFMExampleExpressions.cpp b/examples/SFMExampleExpressions.cpp
index e9c9e920d..df5488ec3 100644
--- a/examples/SFMExampleExpressions.cpp
+++ b/examples/SFMExampleExpressions.cpp
@@ -84,7 +84,7 @@ int main(int argc, char* argv[]) {
// Create perturbed initial
Values initial;
- Pose3 delta(Rot3::rodriguez(-0.1, 0.2, 0.25), Point3(0.05, -0.10, 0.20));
+ Pose3 delta(Rot3::Rodrigues(-0.1, 0.2, 0.25), Point3(0.05, -0.10, 0.20));
for (size_t i = 0; i < poses.size(); ++i)
initial.insert(Symbol('x', i), poses[i].compose(delta));
for (size_t j = 0; j < points.size(); ++j)
diff --git a/examples/SFMExample_SmartFactor.cpp b/examples/SFMExample_SmartFactor.cpp
index fce046a59..bb8935439 100644
--- a/examples/SFMExample_SmartFactor.cpp
+++ b/examples/SFMExample_SmartFactor.cpp
@@ -34,6 +34,9 @@ using namespace gtsam;
// Make the typename short so it looks much cleaner
typedef SmartProjectionPoseFactor SmartFactor;
+// create a typedef to the camera type
+typedef PinholePose Camera;
+
/* ************************************************************************* */
int main(int argc, char* argv[]) {
@@ -55,12 +58,12 @@ int main(int argc, char* argv[]) {
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());
+ SmartFactor::shared_ptr smartfactor(new SmartFactor(K));
for (size_t i = 0; i < poses.size(); ++i) {
// generate the 2D measurement
- SimpleCamera camera(poses[i], *K);
+ Camera 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:
@@ -68,7 +71,7 @@ int main(int argc, char* argv[]) {
// 2. the corresponding camera's key
// 3. camera noise model
// 4. camera calibration
- smartfactor->add(measurement, i, measurementNoise, K);
+ smartfactor->add(measurement, i, measurementNoise);
}
// insert the smart factor in the graph
@@ -77,24 +80,24 @@ int main(int argc, char* argv[]) {
// 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(
+ noiseModel::Diagonal::shared_ptr noise = noiseModel::Diagonal::Sigmas(
(Vector(6) << Vector3::Constant(0.3), Vector3::Constant(0.1)).finished());
- graph.push_back(PriorFactor(0, poses[0], poseNoise));
+ graph.push_back(PriorFactor(0, Camera(poses[0],K), noise));
// Because the structure-from-motion problem has a scale ambiguity, the problem is
// still under-constrained. Here we add a prior on the second pose x1, so this will
// fix the scale by indicating the distance between x0 and x1.
// Because these two are fixed, the rest of the poses will be also be fixed.
- graph.push_back(PriorFactor(1, poses[1], poseNoise)); // add directly to graph
+ graph.push_back(PriorFactor(1, Camera(poses[1],K), noise)); // add directly to graph
graph.print("Factor Graph:\n");
// Create the initial estimate to the solution
// Intentionally initialize the variables off from the ground truth
Values initialEstimate;
- Pose3 delta(Rot3::rodriguez(-0.1, 0.2, 0.25), Point3(0.05, -0.10, 0.20));
+ Pose3 delta(Rot3::Rodrigues(-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));
+ initialEstimate.insert(i, Camera(poses[i].compose(delta), K));
initialEstimate.print("Initial Estimates:\n");
// Optimize the graph and print results
diff --git a/examples/SFMExample_SmartFactorPCG.cpp b/examples/SFMExample_SmartFactorPCG.cpp
index 49482292f..7ec5f8268 100644
--- a/examples/SFMExample_SmartFactorPCG.cpp
+++ b/examples/SFMExample_SmartFactorPCG.cpp
@@ -30,6 +30,9 @@ using namespace gtsam;
// Make the typename short so it looks much cleaner
typedef SmartProjectionPoseFactor SmartFactor;
+// create a typedef to the camera type
+typedef PinholePose Camera;
+
/* ************************************************************************* */
int main(int argc, char* argv[]) {
@@ -51,16 +54,16 @@ int main(int argc, char* argv[]) {
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());
+ SmartFactor::shared_ptr smartfactor(new SmartFactor(K));
for (size_t i = 0; i < poses.size(); ++i) {
// generate the 2D measurement
- SimpleCamera camera(poses[i], *K);
+ Camera 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);
+ smartfactor->add(measurement, i, measurementNoise);
}
// insert the smart factor in the graph
@@ -69,18 +72,18 @@ int main(int argc, char* argv[]) {
// 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(
+ noiseModel::Diagonal::shared_ptr noise = noiseModel::Diagonal::Sigmas(
(Vector(6) << Vector3::Constant(0.3), Vector3::Constant(0.1)).finished());
- graph.push_back(PriorFactor(0, poses[0], poseNoise));
+ graph.push_back(PriorFactor(0, Camera(poses[0],K), noise));
// Fix the scale ambiguity by adding a prior
- graph.push_back(PriorFactor(1, poses[1], poseNoise));
+ graph.push_back(PriorFactor(1, Camera(poses[0],K), noise));
// 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));
+ Pose3 delta(Rot3::Rodrigues(-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));
+ initialEstimate.insert(i, Camera(poses[i].compose(delta),K));
// We will use LM in the outer optimization loop, but by specifying "Iterative" below
// We indicate that an iterative linear solver should be used.
diff --git a/examples/SFMExample_bal_COLAMD_METIS.cpp b/examples/SFMExample_bal_COLAMD_METIS.cpp
new file mode 100644
index 000000000..4bbaac3ef
--- /dev/null
+++ b/examples/SFMExample_bal_COLAMD_METIS.cpp
@@ -0,0 +1,144 @@
+/* ----------------------------------------------------------------------------
+
+ * 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.cpp
+ * @brief This file is to compare the ordering performance for COLAMD vs METIS.
+ * Example problem is to solve a structure-from-motion problem from a "Bundle Adjustment in the Large" file.
+ * @author Frank Dellaert, Zhaoyang Lv
+ */
+
+// For an explanation of headers, see SFMExample.cpp
+#include
+#include
+#include
+#include
+#include
+#include
+#include // for loading BAL datasets !
+
+#include
+
+#include
+
+using namespace std;
+using namespace gtsam;
+using symbol_shorthand::C;
+using symbol_shorthand::P;
+
+// We will be using a projection factor that ties a SFM_Camera to a 3D point.
+// An SFM_Camera is defined in datase.h as a camera with unknown Cal3Bundler calibration
+// and has a total of 9 free parameters
+typedef GeneralSFMFactor MyFactor;
+
+/* ************************************************************************* */
+int main (int argc, char* argv[]) {
+
+ // Find default file, but if an argument is given, try loading a file
+ string filename = findExampleDataFile("dubrovnik-3-7-pre");
+ if (argc>1) filename = string(argv[1]);
+
+ // Load the SfM data from file
+ SfM_data mydata;
+ readBAL(filename, mydata);
+ cout << boost::format("read %1% tracks on %2% cameras\n") % mydata.number_tracks() % mydata.number_cameras();
+
+ // Create a factor graph
+ NonlinearFactorGraph graph;
+
+ // We share *one* noiseModel between all projection factors
+ noiseModel::Isotropic::shared_ptr noise =
+ noiseModel::Isotropic::Sigma(2, 1.0); // one pixel in u and v
+
+ // Add measurements to the factor graph
+ size_t j = 0;
+ BOOST_FOREACH(const SfM_Track& track, mydata.tracks) {
+ BOOST_FOREACH(const SfM_Measurement& m, track.measurements) {
+ size_t i = m.first;
+ Point2 uv = m.second;
+ graph.push_back(MyFactor(uv, noise, C(i), P(j))); // note use of shorthand symbols C and P
+ }
+ j += 1;
+ }
+
+ // Add a prior on pose x1. This indirectly specifies where the origin is.
+ // and a prior on the position of the first landmark to fix the scale
+ graph.push_back(PriorFactor(C(0), mydata.cameras[0], noiseModel::Isotropic::Sigma(9, 0.1)));
+ graph.push_back(PriorFactor (P(0), mydata.tracks[0].p, noiseModel::Isotropic::Sigma(3, 0.1)));
+
+ // Create initial estimate
+ Values initial;
+ size_t i = 0; j = 0;
+ BOOST_FOREACH(const SfM_Camera& camera, mydata.cameras) initial.insert(C(i++), camera);
+ BOOST_FOREACH(const SfM_Track& track, mydata.tracks) initial.insert(P(j++), track.p);
+
+ /** --------------- COMPARISON -----------------------**/
+ /** ----------------------------------------------------**/
+
+ LevenbergMarquardtParams params_using_COLAMD, params_using_METIS;
+ try {
+ params_using_METIS.setVerbosity("ERROR");
+ gttic_(METIS_ORDERING);
+ params_using_METIS.ordering = Ordering::Create(Ordering::METIS, graph);
+ gttoc_(METIS_ORDERING);
+
+ params_using_COLAMD.setVerbosity("ERROR");
+ gttic_(COLAMD_ORDERING);
+ params_using_COLAMD.ordering = Ordering::Create(Ordering::COLAMD, graph);
+ gttoc_(COLAMD_ORDERING);
+ } catch (exception& e) {
+ cout << e.what();
+ }
+
+ // expect they have different ordering results
+ if(params_using_COLAMD.ordering == params_using_METIS.ordering) {
+ cout << "COLAMD and METIS produce the same ordering. "
+ << "Problem here!!!" << endl;
+ }
+
+ /* Optimize the graph with METIS and COLAMD and time the results */
+
+ Values result_METIS, result_COLAMD;
+ try {
+ gttic_(OPTIMIZE_WITH_METIS);
+ LevenbergMarquardtOptimizer lm_METIS(graph, initial, params_using_METIS);
+ result_METIS = lm_METIS.optimize();
+ gttoc_(OPTIMIZE_WITH_METIS);
+
+ gttic_(OPTIMIZE_WITH_COLAMD);
+ LevenbergMarquardtOptimizer lm_COLAMD(graph, initial, params_using_COLAMD);
+ result_COLAMD = lm_COLAMD.optimize();
+ gttoc_(OPTIMIZE_WITH_COLAMD);
+ } catch (exception& e) {
+ cout << e.what();
+ }
+
+
+ { // printing the result
+
+ cout << "COLAMD final error: " << graph.error(result_COLAMD) << endl;
+ cout << "METIS final error: " << graph.error(result_METIS) << endl;
+
+ cout << endl << endl;
+
+ cout << "Time comparison by solving " << filename << " results:" << endl;
+ cout << boost::format("%1% point tracks and %2% cameras\n") \
+ % mydata.number_tracks() % mydata.number_cameras() \
+ << endl;
+
+ tictoc_print_();
+ }
+
+
+ return 0;
+}
+/* ************************************************************************* */
+
diff --git a/examples/SelfCalibrationExample.cpp b/examples/SelfCalibrationExample.cpp
index 8ebf005ab..f5702e7fb 100644
--- a/examples/SelfCalibrationExample.cpp
+++ b/examples/SelfCalibrationExample.cpp
@@ -82,7 +82,7 @@ int main(int argc, char* argv[]) {
Values initialEstimate;
initialEstimate.insert(Symbol('K', 0), Cal3_S2(60.0, 60.0, 0.0, 45.0, 45.0));
for (size_t i = 0; i < poses.size(); ++i)
- initialEstimate.insert(Symbol('x', i), poses[i].compose(Pose3(Rot3::rodriguez(-0.1, 0.2, 0.25), Point3(0.05, -0.10, 0.20))));
+ initialEstimate.insert(Symbol('x', i), poses[i].compose(Pose3(Rot3::Rodrigues(-0.1, 0.2, 0.25), Point3(0.05, -0.10, 0.20))));
for (size_t j = 0; j < points.size(); ++j)
initialEstimate.insert(Symbol('l', j), points[j].compose(Point3(-0.25, 0.20, 0.15)));
diff --git a/examples/SolverComparer.cpp b/examples/SolverComparer.cpp
index 0393affe1..068846884 100644
--- a/examples/SolverComparer.cpp
+++ b/examples/SolverComparer.cpp
@@ -44,6 +44,7 @@
#include
#include
#include
+#include // for GTSAM_USE_TBB
#include
#include
@@ -575,7 +576,7 @@ void runStats()
{
cout << "Gathering statistics..." << endl;
GaussianFactorGraph linear = *datasetMeasurements.linearize(initial);
- GaussianJunctionTree jt(GaussianEliminationTree(linear, Ordering::colamd(linear)));
+ GaussianJunctionTree jt(GaussianEliminationTree(linear, Ordering::Colamd(linear)));
treeTraversal::ForestStatistics statistics = treeTraversal::GatherStatistics(jt);
ofstream file;
diff --git a/examples/TimeTBB.cpp b/examples/TimeTBB.cpp
index a35980836..602a00593 100644
--- a/examples/TimeTBB.cpp
+++ b/examples/TimeTBB.cpp
@@ -17,6 +17,7 @@
#include
#include
+
#include
#include
#include