Enabled more unit tests and either fixed them or have them print a "disabled" message during make check
							parent
							
								
									f4d816dcf8
								
							
						
					
					
						commit
						517a5037a7
					
				| 
						 | 
				
			
			@ -25,15 +25,7 @@ set (slam_full_libs
 | 
			
		|||
 | 
			
		||||
# Exclude tests that don't work
 | 
			
		||||
set (slam_excluded_tests
 | 
			
		||||
    "${CMAKE_CURRENT_SOURCE_DIR}/tests/testAHRS.cpp"
 | 
			
		||||
    "${CMAKE_CURRENT_SOURCE_DIR}/tests/testCombinedImuFactor.cpp"
 | 
			
		||||
    "${CMAKE_CURRENT_SOURCE_DIR}/tests/testImuFactor.cpp"
 | 
			
		||||
    "${CMAKE_CURRENT_SOURCE_DIR}/tests/testInvDepthFactor3.cpp"
 | 
			
		||||
    "${CMAKE_CURRENT_SOURCE_DIR}/tests/testInvDepthFactorVariant1.cpp"
 | 
			
		||||
    "${CMAKE_CURRENT_SOURCE_DIR}/tests/testInvDepthFactorVariant2.cpp"
 | 
			
		||||
    "${CMAKE_CURRENT_SOURCE_DIR}/tests/testInvDepthFactorVariant3.cpp"
 | 
			
		||||
    "${CMAKE_CURRENT_SOURCE_DIR}/tests/testMultiProjectionFactor.cpp"
 | 
			
		||||
    "${CMAKE_CURRENT_SOURCE_DIR}/tests/testSerialization.cpp"
 | 
			
		||||
#    "${CMAKE_CURRENT_SOURCE_DIR}/tests/testSerialization.cpp"
 | 
			
		||||
#    ""  # Add to this list, with full path, to exclude
 | 
			
		||||
)
 | 
			
		||||
# Add all tests
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -49,7 +49,7 @@ TEST( InvDepthFactor, optimize) {
 | 
			
		|||
  InverseDepthFactor::shared_ptr factor(new InverseDepthFactor(expected_uv, sigma,
 | 
			
		||||
      Symbol('x',1), Symbol('l',1), Symbol('d',1), K));
 | 
			
		||||
  graph.push_back(factor);
 | 
			
		||||
  graph.add(PoseConstraint(Symbol('x',1),level_pose));
 | 
			
		||||
  graph += PoseConstraint(Symbol('x',1),level_pose);
 | 
			
		||||
  initial.insert(Symbol('x',1), level_pose);
 | 
			
		||||
  initial.insert(Symbol('l',1), inv_landmark);
 | 
			
		||||
  initial.insert(Symbol('d',1), inv_depth);
 | 
			
		||||
| 
						 | 
				
			
			@ -75,7 +75,7 @@ TEST( InvDepthFactor, optimize) {
 | 
			
		|||
      Symbol('x',2), Symbol('l',1),Symbol('d',1),K));
 | 
			
		||||
  graph.push_back(factor1);
 | 
			
		||||
 | 
			
		||||
  graph.add(PoseConstraint(Symbol('x',2),right_pose));
 | 
			
		||||
  graph += PoseConstraint(Symbol('x',2),right_pose);
 | 
			
		||||
 | 
			
		||||
  initial.insert(Symbol('x',2), right_pose);
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -16,7 +16,6 @@
 | 
			
		|||
 *  @date Nov 2009
 | 
			
		||||
 */
 | 
			
		||||
 | 
			
		||||
#include <gtsam_unstable/nonlinear/ConcurrentBatchFilter.h>
 | 
			
		||||
#include <gtsam/slam/PriorFactor.h>
 | 
			
		||||
#include <gtsam/slam/BetweenFactor.h>
 | 
			
		||||
#include <gtsam/slam/ProjectionFactor.h>
 | 
			
		||||
| 
						 | 
				
			
			@ -25,10 +24,10 @@
 | 
			
		|||
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
 | 
			
		||||
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
 | 
			
		||||
#include <gtsam/nonlinear/LinearContainerFactor.h>
 | 
			
		||||
#include <gtsam/nonlinear/Ordering.h>
 | 
			
		||||
#include <gtsam/inference/Ordering.h>
 | 
			
		||||
#include <gtsam/nonlinear/Values.h>
 | 
			
		||||
#include <gtsam/nonlinear/Symbol.h>
 | 
			
		||||
#include <gtsam/nonlinear/Key.h>
 | 
			
		||||
#include <gtsam/inference/Key.h>
 | 
			
		||||
#include <gtsam/inference/JunctionTree.h>
 | 
			
		||||
#include <gtsam/geometry/Pose3.h>
 | 
			
		||||
#include <gtsam/geometry/Point3.h>
 | 
			
		||||
| 
						 | 
				
			
			@ -76,7 +75,7 @@ TEST( MultiProjectionFactor, create ){
 | 
			
		|||
  views.insert(x3);
 | 
			
		||||
 | 
			
		||||
  MultiProjectionFactor<Pose3, Point3> mpFactor(n_measPixel, noiseProjection, views, l1, K);
 | 
			
		||||
  graph.add(mpFactor);
 | 
			
		||||
  graph += mpFactor;
 | 
			
		||||
 | 
			
		||||
 | 
			
		||||
}
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -8,6 +8,14 @@
 | 
			
		|||
 */
 | 
			
		||||
 | 
			
		||||
#include <CppUnitLite/TestHarness.h>
 | 
			
		||||
#include <iostream>
 | 
			
		||||
 | 
			
		||||
TEST(testSerialization, disabled)
 | 
			
		||||
{
 | 
			
		||||
  CHECK(("*** testSerialization in gtsam_unstable/slam is disabled *** - Needs conversion for unordered", 0));
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
#if 0
 | 
			
		||||
 | 
			
		||||
#include <gtsam/slam/serialization.h>
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			@ -117,6 +125,8 @@ TEST( testSerialization, serialization_file ) {
 | 
			
		|||
  EXPECT(assert_equal(values, actValuesXML));
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
#endif
 | 
			
		||||
 | 
			
		||||
/* ************************************************************************* */
 | 
			
		||||
int main() { TestResult tr; return TestRegistry::runAllTests(tr); }
 | 
			
		||||
/* ************************************************************************* */
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
		Loading…
	
		Reference in New Issue