From fe235b120916ce624666205e9fac5c5c21bacfeb Mon Sep 17 00:00:00 2001 From: Richard Roberts Date: Sat, 7 Jun 2014 19:02:11 -0700 Subject: [PATCH] Building timing scripts using new timing script support in GtsamTesting.cmake. Fixed compile errors in timing scripts but disabled a couple. --- CMakeLists.txt | 3 +++ gtsam/base/CMakeLists.txt | 6 ------ gtsam/discrete/CMakeLists.txt | 6 ------ gtsam/geometry/CMakeLists.txt | 6 ------ gtsam/inference/CMakeLists.txt | 6 ------ gtsam/linear/CMakeLists.txt | 5 ----- gtsam/navigation/CMakeLists.txt | 5 ----- gtsam/nonlinear/CMakeLists.txt | 6 ------ gtsam/slam/CMakeLists.txt | 5 ----- gtsam/symbolic/CMakeLists.txt | 6 ------ gtsam_unstable/CMakeLists.txt | 7 ++++--- gtsam_unstable/base/CMakeLists.txt | 5 ----- gtsam_unstable/timing/CMakeLists.txt | 1 + .../tests => timing}/timeDSFvariants.cpp | 0 .../tests => timing}/timeDSFvariants.xlsx | Bin .../tests => timing}/timeDSFvariants2.xlsx | Bin .../timeInertialNavFactor_GlobalVelocity.cpp | 18 +++++++++--------- tests/CMakeLists.txt | 13 ------------- timing/CMakeLists.txt | 6 ++++++ {tests => timing}/timeBatch.cpp | 0 .../tests => timing}/timeCalibratedCamera.cpp | 4 ++-- .../tests => timing}/timeFactorOverhead.cpp | 0 .../tests => timing}/timeGaussianFactor.cpp | 13 +++++++------ {tests => timing}/timeGaussianFactorGraph.cpp | 18 +++++++----------- {tests => timing}/timeIncremental.cpp | 0 {gtsam/slam/tests => timing}/timeLago.cpp | 0 {gtsam/base/tests => timing}/timeMatrix.cpp | 2 +- .../base/tests => timing}/timeMatrixOps.cpp | 0 .../tests => timing}/timePinholeCamera.cpp | 2 +- .../geometry/tests => timing}/timePose2.cpp | 2 +- .../geometry/tests => timing}/timePose3.cpp | 4 ++-- {gtsam/geometry/tests => timing}/timeRot2.cpp | 0 {gtsam/geometry/tests => timing}/timeRot3.cpp | 0 .../linear/tests => timing}/timeSLAMlike.cpp | 0 .../tests => timing}/timeStereoCamera.cpp | 2 +- {gtsam/base/tests => timing}/timeTest.cpp | 0 {gtsam/base/tests => timing}/timeVirtual.cpp | 0 {gtsam/base/tests => timing}/timeVirtual2.cpp | 0 {tests => timing}/timeiSAM2Chain.cpp | 0 39 files changed, 45 insertions(+), 106 deletions(-) create mode 100644 gtsam_unstable/timing/CMakeLists.txt rename gtsam_unstable/{base/tests => timing}/timeDSFvariants.cpp (100%) rename gtsam_unstable/{base/tests => timing}/timeDSFvariants.xlsx (100%) rename gtsam_unstable/{base/tests => timing}/timeDSFvariants2.xlsx (100%) rename gtsam_unstable/{slam/tests => timing}/timeInertialNavFactor_GlobalVelocity.cpp (86%) create mode 100644 timing/CMakeLists.txt rename {tests => timing}/timeBatch.cpp (100%) rename {gtsam/geometry/tests => timing}/timeCalibratedCamera.cpp (96%) rename {gtsam/linear/tests => timing}/timeFactorOverhead.cpp (100%) rename {gtsam/linear/tests => timing}/timeGaussianFactor.cpp (92%) rename {tests => timing}/timeGaussianFactorGraph.cpp (91%) rename {tests => timing}/timeIncremental.cpp (100%) rename {gtsam/slam/tests => timing}/timeLago.cpp (100%) rename {gtsam/base/tests => timing}/timeMatrix.cpp (99%) rename {gtsam/base/tests => timing}/timeMatrixOps.cpp (100%) rename {gtsam/geometry/tests => timing}/timePinholeCamera.cpp (98%) rename {gtsam/geometry/tests => timing}/timePose2.cpp (99%) rename {gtsam/geometry/tests => timing}/timePose3.cpp (90%) rename {gtsam/geometry/tests => timing}/timeRot2.cpp (100%) rename {gtsam/geometry/tests => timing}/timeRot3.cpp (100%) rename {gtsam/linear/tests => timing}/timeSLAMlike.cpp (100%) rename {gtsam/geometry/tests => timing}/timeStereoCamera.cpp (96%) rename {gtsam/base/tests => timing}/timeTest.cpp (100%) rename {gtsam/base/tests => timing}/timeVirtual.cpp (100%) rename {gtsam/base/tests => timing}/timeVirtual2.cpp (100%) rename {tests => timing}/timeiSAM2Chain.cpp (100%) diff --git a/CMakeLists.txt b/CMakeLists.txt index 010d4de65..d64814829 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -303,6 +303,9 @@ add_subdirectory(tests) # Build examples add_subdirectory(examples) +# Build timing +add_subdirectory(timing) + # Matlab toolbox if (GTSAM_INSTALL_MATLAB_TOOLBOX) add_subdirectory(matlab) diff --git a/gtsam/base/CMakeLists.txt b/gtsam/base/CMakeLists.txt index 50145846e..66d3ec721 100644 --- a/gtsam/base/CMakeLists.txt +++ b/gtsam/base/CMakeLists.txt @@ -7,9 +7,3 @@ install(FILES ${base_headers_tree} DESTINATION include/gtsam/base/treeTraversal) # Build tests add_subdirectory(tests) - -# Build timing scripts -if (GTSAM_BUILD_TIMING) - gtsam_add_subdir_timing(base "gtsam" "gtsam" "${base_excluded_files}") -endif(GTSAM_BUILD_TIMING) - diff --git a/gtsam/discrete/CMakeLists.txt b/gtsam/discrete/CMakeLists.txt index 3c5602080..d78dff34f 100644 --- a/gtsam/discrete/CMakeLists.txt +++ b/gtsam/discrete/CMakeLists.txt @@ -6,9 +6,3 @@ install(FILES ${discrete_headers} DESTINATION include/gtsam/discrete) # Add all tests add_subdirectory(tests) - -# Build timing scripts -#if (GTSAM_BUILD_TIMING) -# gtsam_add_timing(discrete "${discrete_local_libs}") -#endif(GTSAM_BUILD_TIMING) - diff --git a/gtsam/geometry/CMakeLists.txt b/gtsam/geometry/CMakeLists.txt index f72f965ea..dabdde45c 100644 --- a/gtsam/geometry/CMakeLists.txt +++ b/gtsam/geometry/CMakeLists.txt @@ -4,9 +4,3 @@ install(FILES ${geometry_headers} DESTINATION include/gtsam/geometry) # Build tests add_subdirectory(tests) - -# Build timing scripts -if (GTSAM_BUILD_TIMING) - gtsam_add_subdir_timing(geometry "gtsam" "gtsam" "${geometry_excluded_files}") -endif(GTSAM_BUILD_TIMING) - diff --git a/gtsam/inference/CMakeLists.txt b/gtsam/inference/CMakeLists.txt index d5c37d976..c3df3a989 100644 --- a/gtsam/inference/CMakeLists.txt +++ b/gtsam/inference/CMakeLists.txt @@ -4,9 +4,3 @@ install(FILES ${inference_headers} DESTINATION include/gtsam/inference) # Build tests add_subdirectory(tests) - -# Build timing scripts -if (GTSAM_BUILD_TIMING) - gtsam_add_subdir_timing(inference "gtsam" "gtsam" "${inference_excluded_files}") -endif(GTSAM_BUILD_TIMING) - diff --git a/gtsam/linear/CMakeLists.txt b/gtsam/linear/CMakeLists.txt index 29eb60b93..084c27057 100644 --- a/gtsam/linear/CMakeLists.txt +++ b/gtsam/linear/CMakeLists.txt @@ -4,8 +4,3 @@ install(FILES ${linear_headers} DESTINATION include/gtsam/linear) # Build tests add_subdirectory(tests) - -# Build timing scripts -if (GTSAM_BUILD_TIMING) - gtsam_add_subdir_timing(linear "gtsam" "gtsam" "${linear_excluded_files}") -endif(GTSAM_BUILD_TIMING) diff --git a/gtsam/navigation/CMakeLists.txt b/gtsam/navigation/CMakeLists.txt index 3e82af774..e2b2fdce6 100644 --- a/gtsam/navigation/CMakeLists.txt +++ b/gtsam/navigation/CMakeLists.txt @@ -4,8 +4,3 @@ install(FILES ${navigation_headers} DESTINATION include/gtsam/navigation) # Add all tests add_subdirectory(tests) - -# Build timing scripts -if (GTSAM_BUILD_TIMING) - gtsam_add_subdir_timing(navigation "gtsam" "gtsam" "${navigation_excluded_files}") -endif(GTSAM_BUILD_TIMING) diff --git a/gtsam/nonlinear/CMakeLists.txt b/gtsam/nonlinear/CMakeLists.txt index b4d288104..5bb2bd7d2 100644 --- a/gtsam/nonlinear/CMakeLists.txt +++ b/gtsam/nonlinear/CMakeLists.txt @@ -4,9 +4,3 @@ install(FILES ${nonlinear_headers} DESTINATION include/gtsam/nonlinear) # Build tests add_subdirectory(tests) - -# Build timing scripts -if (GTSAM_BUILD_TIMING) - gtsam_add_subdir_timing(nonlinear "gtsam" "gtsam" "${nonlinear_excluded_files}") -endif(GTSAM_BUILD_TIMING) - diff --git a/gtsam/slam/CMakeLists.txt b/gtsam/slam/CMakeLists.txt index b348c4aa3..22645973d 100644 --- a/gtsam/slam/CMakeLists.txt +++ b/gtsam/slam/CMakeLists.txt @@ -8,8 +8,3 @@ install(FILES ${slam_headers} DESTINATION include/gtsam/slam) # Build tests add_subdirectory(tests) - -# Build timing scripts -if (GTSAM_BUILD_TIMING) - gtsam_add_subdir_timing(slam "gtsam" "gtsam" "${slam_excluded_files}") -endif(GTSAM_BUILD_TIMING) diff --git a/gtsam/symbolic/CMakeLists.txt b/gtsam/symbolic/CMakeLists.txt index 6535755f8..feb073f69 100644 --- a/gtsam/symbolic/CMakeLists.txt +++ b/gtsam/symbolic/CMakeLists.txt @@ -4,9 +4,3 @@ install(FILES ${symbolic_headers} DESTINATION include/gtsam/symbolic) # Build tests add_subdirectory(tests) - -# Build timing scripts -if (GTSAM_BUILD_TIMING) - gtsam_add_subdir_timing(symbolic "gtsam" "gtsam" "${symbolic_excluded_files}") -endif(GTSAM_BUILD_TIMING) - diff --git a/gtsam_unstable/CMakeLists.txt b/gtsam_unstable/CMakeLists.txt index a33a4548c..6acb51ff6 100644 --- a/gtsam_unstable/CMakeLists.txt +++ b/gtsam_unstable/CMakeLists.txt @@ -118,6 +118,7 @@ endif(GTSAM_INSTALL_MATLAB_TOOLBOX) # Build examples -if (GTSAM_BUILD_EXAMPLES) - add_subdirectory(examples) -endif(GTSAM_BUILD_EXAMPLES) +add_subdirectory(examples) + +# Build timing +add_subdirectory(timing) diff --git a/gtsam_unstable/base/CMakeLists.txt b/gtsam_unstable/base/CMakeLists.txt index d83e97d26..2cb96be36 100644 --- a/gtsam_unstable/base/CMakeLists.txt +++ b/gtsam_unstable/base/CMakeLists.txt @@ -4,8 +4,3 @@ install(FILES ${base_headers} DESTINATION include/gtsam_unstable/base) # Add all tests add_subdirectory(tests) - -# Build timing scripts -if (GTSAM_BUILD_TIMING) - gtsam_add_subdir_timing(base_unstable "${base_full_libs}" "${base_full_libs}" "${base_excluded_files}") -endif(GTSAM_BUILD_TIMING) diff --git a/gtsam_unstable/timing/CMakeLists.txt b/gtsam_unstable/timing/CMakeLists.txt new file mode 100644 index 000000000..b5130ae92 --- /dev/null +++ b/gtsam_unstable/timing/CMakeLists.txt @@ -0,0 +1 @@ +gtsamAddTimingGlob("*.cpp" "" "gtsam_unstable") diff --git a/gtsam_unstable/base/tests/timeDSFvariants.cpp b/gtsam_unstable/timing/timeDSFvariants.cpp similarity index 100% rename from gtsam_unstable/base/tests/timeDSFvariants.cpp rename to gtsam_unstable/timing/timeDSFvariants.cpp diff --git a/gtsam_unstable/base/tests/timeDSFvariants.xlsx b/gtsam_unstable/timing/timeDSFvariants.xlsx similarity index 100% rename from gtsam_unstable/base/tests/timeDSFvariants.xlsx rename to gtsam_unstable/timing/timeDSFvariants.xlsx diff --git a/gtsam_unstable/base/tests/timeDSFvariants2.xlsx b/gtsam_unstable/timing/timeDSFvariants2.xlsx similarity index 100% rename from gtsam_unstable/base/tests/timeDSFvariants2.xlsx rename to gtsam_unstable/timing/timeDSFvariants2.xlsx diff --git a/gtsam_unstable/slam/tests/timeInertialNavFactor_GlobalVelocity.cpp b/gtsam_unstable/timing/timeInertialNavFactor_GlobalVelocity.cpp similarity index 86% rename from gtsam_unstable/slam/tests/timeInertialNavFactor_GlobalVelocity.cpp rename to gtsam_unstable/timing/timeInertialNavFactor_GlobalVelocity.cpp index 5132df658..0d514abcd 100644 --- a/gtsam_unstable/slam/tests/timeInertialNavFactor_GlobalVelocity.cpp +++ b/gtsam_unstable/timing/timeInertialNavFactor_GlobalVelocity.cpp @@ -20,9 +20,9 @@ #include #include #include -#include #include #include +#include using namespace std; using namespace gtsam; @@ -32,7 +32,7 @@ gtsam::Rot3 world_R_ECEF( 0.85173, -0.52399, 0, 0.41733, 0.67835, -0.60471); -gtsam::Vector ECEF_omega_earth((Vec(3) << 0.0, 0.0, 7.292115e-5)); +gtsam::Vector ECEF_omega_earth((Vector(3) << 0.0, 0.0, 7.292115e-5)); gtsam::Vector world_omega_earth(world_R_ECEF.matrix() * ECEF_omega_earth); /* ************************************************************************* */ @@ -54,16 +54,16 @@ int main() { gtsam::Key BiasKey1(31); double measurement_dt(0.1); - Vector world_g((Vec(3) << 0.0, 0.0, 9.81)); - Vector world_rho((Vec(3) << 0.0, -1.5724e-05, 0.0)); // NED system - gtsam::Vector ECEF_omega_earth((Vec(3) << 0.0, 0.0, 7.292115e-5)); + Vector world_g((Vector(3) << 0.0, 0.0, 9.81)); + Vector world_rho((Vector(3) << 0.0, -1.5724e-05, 0.0)); // NED system + gtsam::Vector ECEF_omega_earth((Vector(3) << 0.0, 0.0, 7.292115e-5)); gtsam::Vector world_omega_earth(world_R_ECEF.matrix() * ECEF_omega_earth); SharedGaussian model(noiseModel::Isotropic::Sigma(9, 0.1)); // Second test: zero angular motion, some acceleration - generated in matlab - Vector measurement_acc((Vec(3) << 6.501390843381716, -6.763926150509185, -2.300389940090343)); - Vector measurement_gyro((Vec(3) << 0.1, 0.2, 0.3)); + Vector measurement_acc((Vector(3) << 6.501390843381716, -6.763926150509185, -2.300389940090343)); + Vector measurement_gyro((Vector(3) << 0.1, 0.2, 0.3)); InertialNavFactor_GlobalVelocity f(PoseKey1, VelKey1, BiasKey1, PoseKey2, VelKey2, measurement_acc, measurement_gyro, measurement_dt, world_g, world_rho, world_omega_earth, model); @@ -72,7 +72,7 @@ int main() { -0.652537293, 0.709880342, 0.265075427); Point3 t1(2.0,1.0,3.0); Pose3 Pose1(R1, t1); - LieVector Vel1(3,0.5,-0.5,0.4); + LieVector Vel1 = Vector((Vector(3) << 0.5,-0.5,0.4)); Rot3 R2(0.473618898, 0.119523052, 0.872582019, 0.609241153, 0.67099888, -0.422594037, -0.636011287, 0.731761397, 0.244979388); @@ -99,7 +99,7 @@ int main() { GaussianFactorGraph graph; gttic_(LinearizeTiming); for(size_t i = 0; i < 100000; ++i) { - GaussianFactor::shared_ptr g = f.linearize(values, ordering); + GaussianFactor::shared_ptr g = f.linearize(values); graph.push_back(g); } gttoc_(LinearizeTiming); diff --git a/tests/CMakeLists.txt b/tests/CMakeLists.txt index cf81dc762..008dbb78d 100644 --- a/tests/CMakeLists.txt +++ b/tests/CMakeLists.txt @@ -14,16 +14,3 @@ if(MSVC) set_property(SOURCE "${CMAKE_CURRENT_SOURCE_DIR}/testSerializationSLAM.cpp" APPEND PROPERTY COMPILE_FLAGS "/bigobj") endif() - -# Build timing scripts -if (GTSAM_BUILD_TIMING) - # Subdirectory target for timing - does not actually execute the scripts - add_custom_target(timing.tests) - set(is_test FALSE) - - # Build grouped benchmarks - gtsam_add_grouped_scripts("tests" # Use subdirectory as group label - "time*.cpp" timing "Timing Benchmark" # Standard for all timing scripts - "${tests_full_libs}" "${tests_full_libs}" "${tests_exclude}" # Pass in linking and exclusion lists - ${is_test}) -endif (GTSAM_BUILD_TIMING) diff --git a/timing/CMakeLists.txt b/timing/CMakeLists.txt new file mode 100644 index 000000000..1040c7ae1 --- /dev/null +++ b/timing/CMakeLists.txt @@ -0,0 +1,6 @@ +list(APPEND to_exclude + timeFactorOverhead.cpp + timeSLAMlike.cpp) +gtsamAddTimingGlob("*.cpp" "${to_exclude}" "gtsam") + +target_link_libraries(timeGaussianFactorGraph CppUnitLite) diff --git a/tests/timeBatch.cpp b/timing/timeBatch.cpp similarity index 100% rename from tests/timeBatch.cpp rename to timing/timeBatch.cpp diff --git a/gtsam/geometry/tests/timeCalibratedCamera.cpp b/timing/timeCalibratedCamera.cpp similarity index 96% rename from gtsam/geometry/tests/timeCalibratedCamera.cpp rename to timing/timeCalibratedCamera.cpp index 1833579d9..76813c455 100644 --- a/gtsam/geometry/tests/timeCalibratedCamera.cpp +++ b/timing/timeCalibratedCamera.cpp @@ -27,11 +27,11 @@ int main() { int n = 100000; - const Pose3 pose1((Matrix)(Mat(3,3) << + const Pose3 pose1(Matrix3((Matrix(3,3) << 1., 0., 0., 0.,-1., 0., 0., 0.,-1. - ), + )), Point3(0,0,0.5)); const CalibratedCamera camera(pose1); diff --git a/gtsam/linear/tests/timeFactorOverhead.cpp b/timing/timeFactorOverhead.cpp similarity index 100% rename from gtsam/linear/tests/timeFactorOverhead.cpp rename to timing/timeFactorOverhead.cpp diff --git a/gtsam/linear/tests/timeGaussianFactor.cpp b/timing/timeGaussianFactor.cpp similarity index 92% rename from gtsam/linear/tests/timeGaussianFactor.cpp rename to timing/timeGaussianFactor.cpp index 0ffdd1cfa..261fbac48 100644 --- a/gtsam/linear/tests/timeGaussianFactor.cpp +++ b/timing/timeGaussianFactor.cpp @@ -22,7 +22,7 @@ using namespace std; #include -#include // for operator += in Ordering +#include #include #include @@ -33,7 +33,7 @@ using namespace std; using namespace gtsam; using namespace boost::assign; -static const Index _x1_=1, _x2_=2, _l1_=3; +static const Key _x1_=1, _x2_=2, _l1_=3; /* * Alex's Machine @@ -53,7 +53,7 @@ static const Index _x1_=1, _x2_=2, _l1_=3; int main() { // create a linear factor - Matrix Ax2 = (Mat(8, 2) << + Matrix Ax2 = (Matrix(8, 2) << // x2 -5., 0., +0.,-5., @@ -65,7 +65,7 @@ int main() +0.,10. ); - Matrix Al1 = (Mat(8, 10) << + Matrix Al1 = (Matrix(8, 10) << // l1 5., 0.,1.,2.,3.,4.,5.,6.,7.,8., 0., 5.,1.,2.,3.,4.,5.,6.,7.,8., @@ -77,7 +77,7 @@ int main() 0., 0.,1.,2.,3.,4.,5.,6.,7.,8. ); - Matrix Ax1 = (Mat(8, 2) << + Matrix Ax1 = (Matrix(8, 2) << // x1 0.00, 0.,1.,2.,3.,4.,5.,6.,7.,8., 0.00, 0.,1.,2.,3.,4.,5.,6.,7.,8., @@ -108,7 +108,8 @@ int main() JacobianFactor::shared_ptr factor; for(int i = 0; i < n; i++) - conditional = JacobianFactor(combined).eliminateFirst(); + boost::tie(conditional, factor) = + JacobianFactor(combined).eliminate(Ordering(boost::assign::list_of(_x2_))); long timeLog2 = clock(); double seconds = (double)(timeLog2-timeLog)/CLOCKS_PER_SEC; diff --git a/tests/timeGaussianFactorGraph.cpp b/timing/timeGaussianFactorGraph.cpp similarity index 91% rename from tests/timeGaussianFactorGraph.cpp rename to timing/timeGaussianFactorGraph.cpp index 00d24bd13..a3157729e 100644 --- a/tests/timeGaussianFactorGraph.cpp +++ b/timing/timeGaussianFactorGraph.cpp @@ -29,10 +29,10 @@ using namespace boost::assign; /* ************************************************************************* */ // Create a Kalman smoother for t=1:T and optimize double timeKalmanSmoother(int T) { - pair smoother_ordering = createSmoother(T); - GaussianFactorGraph& smoother(smoother_ordering.first); + GaussianFactorGraph smoother = createSmoother(T); clock_t start = clock(); - GaussianSequentialSolver(smoother).optimize(); + // Keys will come out sorted since keys() returns a set + smoother.optimize(Ordering(smoother.keys())); clock_t end = clock (); double dif = (double)(end - start) / CLOCKS_PER_SEC; return dif; @@ -40,12 +40,10 @@ double timeKalmanSmoother(int T) { /* ************************************************************************* */ // Create a planar factor graph and optimize -// todo: use COLAMD ordering again (removed when linear baked-in ordering added) double timePlanarSmoother(int N, bool old = true) { - boost::tuple pg = planarGraph(N); - GaussianFactorGraph& fg(pg.get<0>()); + GaussianFactorGraph fg = planarGraph(N).get<0>(); clock_t start = clock(); - GaussianSequentialSolver(fg).optimize(); + fg.optimize(); clock_t end = clock (); double dif = (double)(end - start) / CLOCKS_PER_SEC; return dif; @@ -53,12 +51,10 @@ double timePlanarSmoother(int N, bool old = true) { /* ************************************************************************* */ // Create a planar factor graph and eliminate -// todo: use COLAMD ordering again (removed when linear baked-in ordering added) double timePlanarSmootherEliminate(int N, bool old = true) { - boost::tuple pg = planarGraph(N); - GaussianFactorGraph& fg(pg.get<0>()); + GaussianFactorGraph fg = planarGraph(N).get<0>(); clock_t start = clock(); - GaussianSequentialSolver(fg).eliminate(); + fg.eliminateMultifrontal(); clock_t end = clock (); double dif = (double)(end - start) / CLOCKS_PER_SEC; return dif; diff --git a/tests/timeIncremental.cpp b/timing/timeIncremental.cpp similarity index 100% rename from tests/timeIncremental.cpp rename to timing/timeIncremental.cpp diff --git a/gtsam/slam/tests/timeLago.cpp b/timing/timeLago.cpp similarity index 100% rename from gtsam/slam/tests/timeLago.cpp rename to timing/timeLago.cpp diff --git a/gtsam/base/tests/timeMatrix.cpp b/timing/timeMatrix.cpp similarity index 99% rename from gtsam/base/tests/timeMatrix.cpp rename to timing/timeMatrix.cpp index 2cd0a8b19..7e1c1b5be 100644 --- a/gtsam/base/tests/timeMatrix.cpp +++ b/timing/timeMatrix.cpp @@ -189,7 +189,7 @@ double timeColumn(size_t reps) { */ double timeHouseholder(size_t reps) { // create a matrix - Matrix Abase = Mat(4, 7) << + Matrix Abase = (Matrix(4, 7) << -5, 0, 5, 0, 0, 0, -1, 00, -5, 0, 5, 0, 0, 1.5, 10, 0, 0, 0,-10, 0, 2, diff --git a/gtsam/base/tests/timeMatrixOps.cpp b/timing/timeMatrixOps.cpp similarity index 100% rename from gtsam/base/tests/timeMatrixOps.cpp rename to timing/timeMatrixOps.cpp diff --git a/gtsam/geometry/tests/timePinholeCamera.cpp b/timing/timePinholeCamera.cpp similarity index 98% rename from gtsam/geometry/tests/timePinholeCamera.cpp rename to timing/timePinholeCamera.cpp index de1fa1279..66a8ca099 100644 --- a/gtsam/geometry/tests/timePinholeCamera.cpp +++ b/timing/timePinholeCamera.cpp @@ -28,7 +28,7 @@ int main() { int n = 1000000; - const Pose3 pose1((Matrix)(Mat(3,3) << + const Pose3 pose1((Matrix)(Matrix(3,3) << 1., 0., 0., 0.,-1., 0., 0., 0.,-1. diff --git a/gtsam/geometry/tests/timePose2.cpp b/timing/timePose2.cpp similarity index 99% rename from gtsam/geometry/tests/timePose2.cpp rename to timing/timePose2.cpp index 28044068c..94bd78ef9 100644 --- a/gtsam/geometry/tests/timePose2.cpp +++ b/timing/timePose2.cpp @@ -58,7 +58,7 @@ Pose2 Pose2betweenOptimized(const Pose2& r1, const Pose2& r2, if (H1) { double dt1 = -s2 * x + c2 * y; double dt2 = -c2 * x - s2 * y; - *H1 = (Mat(3,3) << + *H1 = (Matrix(3,3) << -c, -s, dt1, s, -c, dt2, 0.0, 0.0,-1.0); diff --git a/gtsam/geometry/tests/timePose3.cpp b/timing/timePose3.cpp similarity index 90% rename from gtsam/geometry/tests/timePose3.cpp rename to timing/timePose3.cpp index 13e630706..fa8ef7b6c 100644 --- a/gtsam/geometry/tests/timePose3.cpp +++ b/timing/timePose3.cpp @@ -37,8 +37,8 @@ int main() double norm=sqrt(1.0+16.0+4.0); double x=1.0/norm, y=4.0/norm, z=2.0/norm; - Vector v = (Vec(6) << x, y, z, 0.1, 0.2, -0.1); - Pose3 T = Pose3::Expmap((Vec(6) << 0.1, 0.1, 0.2, 0.1, 0.4, 0.2)), T2 = T.retract(v); + Vector v = (Vector(6) << x, y, z, 0.1, 0.2, -0.1); + Pose3 T = Pose3::Expmap((Vector(6) << 0.1, 0.1, 0.2, 0.1, 0.4, 0.2)), T2 = T.retract(v); Matrix H1,H2; TEST(retract, T.retract(v)) diff --git a/gtsam/geometry/tests/timeRot2.cpp b/timing/timeRot2.cpp similarity index 100% rename from gtsam/geometry/tests/timeRot2.cpp rename to timing/timeRot2.cpp diff --git a/gtsam/geometry/tests/timeRot3.cpp b/timing/timeRot3.cpp similarity index 100% rename from gtsam/geometry/tests/timeRot3.cpp rename to timing/timeRot3.cpp diff --git a/gtsam/linear/tests/timeSLAMlike.cpp b/timing/timeSLAMlike.cpp similarity index 100% rename from gtsam/linear/tests/timeSLAMlike.cpp rename to timing/timeSLAMlike.cpp diff --git a/gtsam/geometry/tests/timeStereoCamera.cpp b/timing/timeStereoCamera.cpp similarity index 96% rename from gtsam/geometry/tests/timeStereoCamera.cpp rename to timing/timeStereoCamera.cpp index bfe4b5aaa..dce622720 100644 --- a/gtsam/geometry/tests/timeStereoCamera.cpp +++ b/timing/timeStereoCamera.cpp @@ -27,7 +27,7 @@ int main() { int n = 100000; - const Pose3 pose1((Matrix)(Mat(3,3) << + const Pose3 pose1((Matrix)(Matrix(3,3) << 1., 0., 0., 0.,-1., 0., 0., 0.,-1. diff --git a/gtsam/base/tests/timeTest.cpp b/timing/timeTest.cpp similarity index 100% rename from gtsam/base/tests/timeTest.cpp rename to timing/timeTest.cpp diff --git a/gtsam/base/tests/timeVirtual.cpp b/timing/timeVirtual.cpp similarity index 100% rename from gtsam/base/tests/timeVirtual.cpp rename to timing/timeVirtual.cpp diff --git a/gtsam/base/tests/timeVirtual2.cpp b/timing/timeVirtual2.cpp similarity index 100% rename from gtsam/base/tests/timeVirtual2.cpp rename to timing/timeVirtual2.cpp diff --git a/tests/timeiSAM2Chain.cpp b/timing/timeiSAM2Chain.cpp similarity index 100% rename from tests/timeiSAM2Chain.cpp rename to timing/timeiSAM2Chain.cpp