Moved tests and timing scripts into subfolders
parent
5ab154e654
commit
f0b424a3d1
|
|
@ -9,11 +9,11 @@ check_PROGRAMS =
|
||||||
|
|
||||||
# base Math
|
# base Math
|
||||||
sources += Vector.cpp svdcmp.cpp Matrix.cpp
|
sources += Vector.cpp svdcmp.cpp Matrix.cpp
|
||||||
check_PROGRAMS += testVector testMatrix
|
check_PROGRAMS += tests/testVector tests/testMatrix
|
||||||
|
|
||||||
if USE_LAPACK
|
if USE_LAPACK
|
||||||
sources += SPQRUtil.cpp
|
sources += SPQRUtil.cpp
|
||||||
check_PROGRAMS += testSPQRUtil
|
check_PROGRAMS += tests/testSPQRUtil
|
||||||
endif
|
endif
|
||||||
|
|
||||||
# Testing
|
# Testing
|
||||||
|
|
@ -25,10 +25,10 @@ headers += Lie.h Lie-inl.h
|
||||||
# Data structures
|
# Data structures
|
||||||
headers += BTree.h DSF.h
|
headers += BTree.h DSF.h
|
||||||
sources += DSFVector.cpp
|
sources += DSFVector.cpp
|
||||||
check_PROGRAMS += testBTree testDSF testDSFVector
|
check_PROGRAMS += tests/testBTree tests/testDSF tests/testDSFVector
|
||||||
|
|
||||||
# Timing tests
|
# Timing tests
|
||||||
noinst_PROGRAMS = timeMatrix
|
noinst_PROGRAMS = tests/timeMatrix
|
||||||
|
|
||||||
#----------------------------------------------------------------------------------------------------
|
#----------------------------------------------------------------------------------------------------
|
||||||
# Create a libtool library that is not installed
|
# Create a libtool library that is not installed
|
||||||
|
|
|
||||||
|
|
@ -8,20 +8,20 @@ check_PROGRAMS =
|
||||||
|
|
||||||
# Points and poses
|
# Points and poses
|
||||||
sources += Point2.cpp Rot2.cpp Pose2.cpp Point3.cpp Rot3.cpp Pose3.cpp
|
sources += Point2.cpp Rot2.cpp Pose2.cpp Point3.cpp Rot3.cpp Pose3.cpp
|
||||||
check_PROGRAMS += testPoint2 testRot2 testPose2 testPoint3 testRot3 testPose3
|
check_PROGRAMS += tests/testPoint2 tests/testRot2 tests/testPose2 tests/testPoint3 tests/testRot3 tests/testPose3
|
||||||
|
|
||||||
# Cameras
|
# Cameras
|
||||||
sources += Cal3_S2.cpp CalibratedCamera.cpp SimpleCamera.cpp
|
sources += Cal3_S2.cpp CalibratedCamera.cpp SimpleCamera.cpp
|
||||||
check_PROGRAMS += testCal3_S2 testCalibratedCamera testSimpleCamera
|
check_PROGRAMS += tests/testCal3_S2 tests/testCalibratedCamera tests/testSimpleCamera
|
||||||
|
|
||||||
# Tensors
|
# Tensors
|
||||||
headers += tensors.h Tensor1.h Tensor2.h Tensor3.h Tensor4.h Tensor5.h
|
headers += tensors.h Tensor1.h Tensor2.h Tensor3.h Tensor4.h Tensor5.h
|
||||||
headers += Tensor1Expression.h Tensor2Expression.h Tensor3Expression.h Tensor5Expression.h
|
headers += Tensor1Expression.h Tensor2Expression.h Tensor3Expression.h Tensor5Expression.h
|
||||||
sources += projectiveGeometry.cpp tensorInterface.cpp
|
sources += projectiveGeometry.cpp tensorInterface.cpp
|
||||||
check_PROGRAMS += testTensors testHomography2 testTrifocal
|
check_PROGRAMS += tests/testTensors tests/testHomography2 tests/testTrifocal
|
||||||
|
|
||||||
# Timing tests
|
# Timing tests
|
||||||
noinst_PROGRAMS = timeRot3
|
noinst_PROGRAMS = tests/timeRot3
|
||||||
|
|
||||||
#----------------------------------------------------------------------------------------------------
|
#----------------------------------------------------------------------------------------------------
|
||||||
# Create a libtool library that is not installed
|
# Create a libtool library that is not installed
|
||||||
|
|
|
||||||
|
|
@ -13,12 +13,12 @@ check_PROGRAMS =
|
||||||
# GTSAM core
|
# GTSAM core
|
||||||
headers += Key.h SymbolMap.h Factor.h Conditional.h IndexTable.h
|
headers += Key.h SymbolMap.h Factor.h Conditional.h IndexTable.h
|
||||||
sources += Ordering.cpp
|
sources += Ordering.cpp
|
||||||
check_PROGRAMS += testOrdering testKey
|
check_PROGRAMS += tests/testOrdering tests/testKey
|
||||||
|
|
||||||
# Symbolic Inference
|
# Symbolic Inference
|
||||||
headers += SymbolicConditional.h
|
headers += SymbolicConditional.h
|
||||||
sources += SymbolicFactor.cpp SymbolicFactorGraph.cpp SymbolicBayesNet.cpp
|
sources += SymbolicFactor.cpp SymbolicFactorGraph.cpp SymbolicBayesNet.cpp
|
||||||
check_PROGRAMS += testSymbolicFactor testSymbolicFactorGraph testSymbolicBayesNet
|
check_PROGRAMS += tests/testSymbolicFactor tests/testSymbolicFactorGraph tests/testSymbolicBayesNet
|
||||||
|
|
||||||
# Inference
|
# Inference
|
||||||
headers += inference.h inference-inl.h
|
headers += inference.h inference-inl.h
|
||||||
|
|
@ -31,7 +31,7 @@ headers += BayesNet.h BayesNet-inl.h
|
||||||
headers += BayesTree.h BayesTree-inl.h
|
headers += BayesTree.h BayesTree-inl.h
|
||||||
headers += ISAM.h ISAM-inl.h
|
headers += ISAM.h ISAM-inl.h
|
||||||
headers += ISAM2.h ISAM2-inl.h
|
headers += ISAM2.h ISAM2-inl.h
|
||||||
check_PROGRAMS += testFactorGraph testClusterTree testEliminationTree testJunctionTree testBayesTree testISAM
|
check_PROGRAMS += tests/testFactorGraph tests/testClusterTree tests/testEliminationTree tests/testJunctionTree tests/testBayesTree tests/testISAM
|
||||||
|
|
||||||
#----------------------------------------------------------------------------------------------------
|
#----------------------------------------------------------------------------------------------------
|
||||||
# discrete
|
# discrete
|
||||||
|
|
@ -39,10 +39,10 @@ check_PROGRAMS += testFactorGraph testClusterTree testEliminationTree testJuncti
|
||||||
|
|
||||||
# Binary Inference
|
# Binary Inference
|
||||||
headers += BinaryConditional.h
|
headers += BinaryConditional.h
|
||||||
check_PROGRAMS += testBinaryBayesNet
|
check_PROGRAMS += tests/testBinaryBayesNet
|
||||||
|
|
||||||
# Timing tests
|
# Timing tests
|
||||||
noinst_PROGRAMS = timeSymbolMaps
|
noinst_PROGRAMS = tests/timeSymbolMaps
|
||||||
|
|
||||||
#----------------------------------------------------------------------------------------------------
|
#----------------------------------------------------------------------------------------------------
|
||||||
# Create a libtool library that is not installed
|
# Create a libtool library that is not installed
|
||||||
|
|
|
||||||
|
|
@ -9,12 +9,12 @@ check_PROGRAMS =
|
||||||
# Noise Model
|
# Noise Model
|
||||||
headers += SharedGaussian.h SharedDiagonal.h
|
headers += SharedGaussian.h SharedDiagonal.h
|
||||||
sources += NoiseModel.cpp Errors.cpp
|
sources += NoiseModel.cpp Errors.cpp
|
||||||
check_PROGRAMS += testNoiseModel testErrors
|
check_PROGRAMS += tests/testNoiseModel tests/testErrors
|
||||||
|
|
||||||
# Vector Configurations
|
# Vector Configurations
|
||||||
headers += VectorConfig.h
|
headers += VectorConfig.h
|
||||||
sources += VectorMap.cpp VectorBTree.cpp
|
sources += VectorMap.cpp VectorBTree.cpp
|
||||||
check_PROGRAMS += testVectorMap testVectorBTree
|
check_PROGRAMS += tests/testVectorMap tests/testVectorBTree
|
||||||
|
|
||||||
# Gaussian Factor Graphs
|
# Gaussian Factor Graphs
|
||||||
headers += GaussianFactorSet.h Factorization.h
|
headers += GaussianFactorSet.h Factorization.h
|
||||||
|
|
@ -22,15 +22,15 @@ sources += GaussianFactor.cpp GaussianFactorGraph.cpp
|
||||||
sources += GaussianJunctionTree.cpp
|
sources += GaussianJunctionTree.cpp
|
||||||
sources += GaussianConditional.cpp GaussianBayesNet.cpp
|
sources += GaussianConditional.cpp GaussianBayesNet.cpp
|
||||||
sources += GaussianISAM.cpp
|
sources += GaussianISAM.cpp
|
||||||
check_PROGRAMS += testGaussianFactor testGaussianJunctionTree testGaussianConditional
|
check_PROGRAMS += tests/testGaussianFactor tests/testGaussianJunctionTree tests/testGaussianConditional
|
||||||
|
|
||||||
# Iterative Methods
|
# Iterative Methods
|
||||||
headers += iterative-inl.h SubgraphSolver.h SubgraphSolver-inl.h
|
headers += iterative-inl.h SubgraphSolver.h SubgraphSolver-inl.h
|
||||||
sources += iterative.cpp BayesNetPreconditioner.cpp SubgraphPreconditioner.cpp
|
sources += iterative.cpp BayesNetPreconditioner.cpp SubgraphPreconditioner.cpp
|
||||||
check_PROGRAMS += testBayesNetPreconditioner
|
check_PROGRAMS += tests/testBayesNetPreconditioner
|
||||||
|
|
||||||
# Timing tests
|
# Timing tests
|
||||||
noinst_PROGRAMS = timeGaussianFactor timeVectorConfig
|
noinst_PROGRAMS = tests/timeGaussianFactor tests/timeVectorConfig
|
||||||
|
|
||||||
#----------------------------------------------------------------------------------------------------
|
#----------------------------------------------------------------------------------------------------
|
||||||
# Create a libtool library that is not installed
|
# Create a libtool library that is not installed
|
||||||
|
|
|
||||||
|
|
@ -13,7 +13,7 @@ check_PROGRAMS =
|
||||||
|
|
||||||
# Lie Groups
|
# Lie Groups
|
||||||
headers += LieConfig.h LieConfig-inl.h TupleConfig.h TupleConfig-inl.h
|
headers += LieConfig.h LieConfig-inl.h TupleConfig.h TupleConfig-inl.h
|
||||||
check_PROGRAMS += testLieConfig
|
check_PROGRAMS += tests/testLieConfig
|
||||||
|
|
||||||
# Nonlinear nonlinear
|
# Nonlinear nonlinear
|
||||||
headers += NonlinearFactorGraph.h NonlinearFactorGraph-inl.h
|
headers += NonlinearFactorGraph.h NonlinearFactorGraph-inl.h
|
||||||
|
|
@ -23,11 +23,11 @@ headers += NonlinearFactor.h
|
||||||
# Nonlinear constraints
|
# Nonlinear constraints
|
||||||
headers += NonlinearConstraint.h NonlinearConstraint-inl.h
|
headers += NonlinearConstraint.h NonlinearConstraint-inl.h
|
||||||
headers += NonlinearEquality.h
|
headers += NonlinearEquality.h
|
||||||
check_PROGRAMS += testNonlinearConstraint
|
check_PROGRAMS += tests/testNonlinearConstraint
|
||||||
|
|
||||||
# SQP
|
# SQP
|
||||||
sources += ConstraintOptimizer.cpp
|
sources += ConstraintOptimizer.cpp
|
||||||
check_PROGRAMS += testConstraintOptimizer
|
check_PROGRAMS += tests/testConstraintOptimizer
|
||||||
|
|
||||||
#----------------------------------------------------------------------------------------------------
|
#----------------------------------------------------------------------------------------------------
|
||||||
# Create a libtool library that is not installed
|
# Create a libtool library that is not installed
|
||||||
|
|
|
||||||
|
|
@ -11,42 +11,42 @@ headers += Simulated2DConfig.h
|
||||||
headers += Simulated2DPosePrior.h Simulated2DPointPrior.h
|
headers += Simulated2DPosePrior.h Simulated2DPointPrior.h
|
||||||
headers += Simulated2DOdometry.h Simulated2DMeasurement.h
|
headers += Simulated2DOdometry.h Simulated2DMeasurement.h
|
||||||
sources += simulated2D.cpp smallExample.cpp
|
sources += simulated2D.cpp smallExample.cpp
|
||||||
check_PROGRAMS += testSimulated2D
|
check_PROGRAMS += tests/testSimulated2D
|
||||||
|
|
||||||
# simulated2DOriented example
|
# simulated2DOriented example
|
||||||
headers += Simulated2DOrientedConfig.h
|
headers += Simulated2DOrientedConfig.h
|
||||||
headers += Simulated2DOrientedPosePrior.h
|
headers += Simulated2DOrientedPosePrior.h
|
||||||
headers += Simulated2DOrientedOdometry.h
|
headers += Simulated2DOrientedOdometry.h
|
||||||
sources += simulated2DOriented.cpp
|
sources += simulated2DOriented.cpp
|
||||||
check_PROGRAMS += testSimulated2DOriented
|
check_PROGRAMS += tests/testSimulated2DOriented
|
||||||
|
|
||||||
# simulated3D example
|
# simulated3D example
|
||||||
sources += Simulated3D.cpp
|
sources += Simulated3D.cpp
|
||||||
check_PROGRAMS += testSimulated3D
|
check_PROGRAMS += tests/testSimulated3D
|
||||||
|
|
||||||
# Pose SLAM headers
|
# Pose SLAM headers
|
||||||
headers += BetweenFactor.h PriorFactor.h
|
headers += BetweenFactor.h PriorFactor.h
|
||||||
|
|
||||||
# 2D Pose SLAM
|
# 2D Pose SLAM
|
||||||
sources += pose2SLAM.cpp Pose2SLAMOptimizer.cpp dataset.cpp
|
sources += pose2SLAM.cpp Pose2SLAMOptimizer.cpp dataset.cpp
|
||||||
check_PROGRAMS += testPose2Factor testPose2Config testPose2SLAM testPose2Prior
|
check_PROGRAMS += tests/testPose2Factor tests/testPose2Config tests/testPose2SLAM tests/testPose2Prior
|
||||||
|
|
||||||
# 2D SLAM using Bearing and Range
|
# 2D SLAM using Bearing and Range
|
||||||
headers += BearingFactor.h RangeFactor.h BearingRangeFactor.h
|
headers += BearingFactor.h RangeFactor.h BearingRangeFactor.h
|
||||||
sources += planarSLAM.cpp
|
sources += planarSLAM.cpp
|
||||||
check_PROGRAMS += testPlanarSLAM
|
check_PROGRAMS += tests/testPlanarSLAM
|
||||||
|
|
||||||
# 3D Pose constraints
|
# 3D Pose constraints
|
||||||
sources += pose3SLAM.cpp
|
sources += pose3SLAM.cpp
|
||||||
check_PROGRAMS += testPose3Factor testPose3Config testPose3SLAM
|
check_PROGRAMS += tests/testPose3Factor tests/testPose3Config tests/testPose3SLAM
|
||||||
|
|
||||||
# Visual SLAM
|
# Visual SLAM
|
||||||
sources += visualSLAM.cpp
|
sources += visualSLAM.cpp
|
||||||
check_PROGRAMS += testVSLAMFactor testVSLAMGraph testVSLAMConfig
|
check_PROGRAMS += tests/testVSLAMFactor tests/testVSLAMGraph tests/testVSLAMConfig
|
||||||
|
|
||||||
# GaussianISAM2 is fairly SLAM-specific
|
# GaussianISAM2 is fairly SLAM-specific
|
||||||
sources += GaussianISAM2.cpp
|
sources += GaussianISAM2.cpp
|
||||||
check_PROGRAMS += testGaussianISAM2
|
check_PROGRAMS += tests/testGaussianISAM2
|
||||||
|
|
||||||
#----------------------------------------------------------------------------------------------------
|
#----------------------------------------------------------------------------------------------------
|
||||||
# Create a libtool library that is not installed
|
# Create a libtool library that is not installed
|
||||||
|
|
|
||||||
Loading…
Reference in New Issue