2010-10-14 12:54:38 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								/* ----------------------------------------------------------------------------
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2019-02-11 22:39:48 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								 * GTSAM Copyright 2010, Georgia Tech Research Corporation,
							 | 
						
					
						
							
								
									
										
										
										
											2010-10-14 12:54:38 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								 * 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
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 * -------------------------------------------------------------------------- */
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/**
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 *  @file  testNonlinearFactor.cpp
							 | 
						
					
						
							
								
									
										
										
										
											2019-02-11 22:39:48 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								 *  @brief Unit tests for Non-Linear Factor,
							 | 
						
					
						
							
								
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								 *  create a non linear factor graph and a values structure for it and
							 | 
						
					
						
							
								
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 *  calculate the error for the factor.
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 *  @author Christian Potthast
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 **/
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/*STL/C++*/
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								#include <iostream>
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2010-10-26 04:10:33 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								#include <CppUnitLite/TestHarness.h>
							 | 
						
					
						
							
								
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2010-01-18 13:38:53 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								// TODO: DANGEROUS, create shared pointers
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								#define GTSAM_MAGIC_GAUSSIAN 2
							 | 
						
					
						
							
								
									
										
										
										
											2011-08-18 21:18:26 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2011-10-20 10:11:28 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								#include <gtsam/base/Testable.h>
							 | 
						
					
						
							
								
									
										
										
										
											2010-08-20 01:23:19 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								#include <gtsam/base/Matrix.h>
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-10 04:15:44 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								#include <tests/smallExample.h>
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								#include <tests/simulated2D.h>
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-06 06:31:33 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								#include <gtsam/linear/GaussianFactor.h>
							 | 
						
					
						
							
								
									
										
										
										
											2011-12-21 07:25:43 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								#include <gtsam/nonlinear/NonlinearFactorGraph.h>
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-19 23:32:16 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								#include <gtsam/inference/Symbol.h>
							 | 
						
					
						
							
								
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								using namespace std;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								using namespace gtsam;
							 | 
						
					
						
							
								
									
										
										
										
											2010-01-19 13:33:44 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								using namespace example;
							 | 
						
					
						
							
								
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-03 00:18:40 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								// Convenience for named keys
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-03 03:28:21 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								using symbol_shorthand::X;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								using symbol_shorthand::L;
							 | 
						
					
						
							
								
									
										
										
										
											2012-02-07 12:02:20 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2012-01-30 12:34:46 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								typedef boost::shared_ptr<NonlinearFactor > shared_nlf;
							 | 
						
					
						
							
								
									
										
										
										
											2009-10-07 02:25:04 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2009-10-25 04:01:47 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/* ************************************************************************* */
							 | 
						
					
						
							
								
									
										
										
										
											2009-11-13 00:47:12 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								TEST( NonlinearFactor, equals )
							 | 
						
					
						
							
								
									
										
										
										
											2009-10-25 04:01:47 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								{
							 | 
						
					
						
							
								
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  SharedNoiseModel sigma(noiseModel::Isotropic::Sigma(2,1.0));
							 | 
						
					
						
							
								
									
										
										
										
											2009-10-25 04:01:47 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  // create two nonlinear2 factors
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  Point2 z3(0.,-1.);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  simulated2D::Measurement f0(z3, sigma, X(1),L(1));
							 | 
						
					
						
							
								
									
										
										
										
											2009-10-25 04:01:47 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  // measurement between x2 and l1
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  Point2 z4(-1.5, -1.);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  simulated2D::Measurement f1(z4, sigma, X(2),L(1));
							 | 
						
					
						
							
								
									
										
										
										
											2009-10-25 04:01:47 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  CHECK(assert_equal(f0,f0));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  CHECK(f0.equals(f0));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  CHECK(!f0.equals(f1));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  CHECK(!f1.equals(f0));
							 | 
						
					
						
							
								
									
										
										
										
											2009-10-25 04:01:47 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								}
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/* ************************************************************************* */
							 | 
						
					
						
							
								
									
										
										
										
											2009-11-13 00:47:12 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								TEST( NonlinearFactor, equals2 )
							 | 
						
					
						
							
								
									
										
										
										
											2009-10-25 04:01:47 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								{
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // create a non linear factor graph
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  NonlinearFactorGraph fg = createNonlinearFactorGraph();
							 | 
						
					
						
							
								
									
										
										
										
											2009-10-25 04:01:47 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // get two factors
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  NonlinearFactorGraph::sharedFactor f0 = fg[0], f1 = fg[1];
							 | 
						
					
						
							
								
									
										
										
										
											2009-10-25 04:01:47 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  CHECK(f0->equals(*f0));
							 | 
						
					
						
							
								
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  CHECK(!f0->equals(*f1));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  CHECK(!f1->equals(*f0));
							 | 
						
					
						
							
								
									
										
										
										
											2009-10-25 04:01:47 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								}
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/* ************************************************************************* */
							 | 
						
					
						
							
								
									
										
										
										
											2009-11-13 00:47:12 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								TEST( NonlinearFactor, NonlinearFactor )
							 | 
						
					
						
							
								
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								{
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // create a non linear factor graph
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  NonlinearFactorGraph fg = createNonlinearFactorGraph();
							 | 
						
					
						
							
								
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  // create a values structure for the non linear factor graph
							 | 
						
					
						
							
								
									
										
										
										
											2012-02-03 00:16:46 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  Values cfg = createNoisyValues();
							 | 
						
					
						
							
								
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // get the factor "f1" from the factor graph
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  NonlinearFactorGraph::sharedFactor factor = fg[0];
							 | 
						
					
						
							
								
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // calculate the error_vector from the factor "f1"
							 | 
						
					
						
							
								
									
										
										
										
											2011-09-03 11:46:19 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  // error_vector = [0.1 0.1]
							 | 
						
					
						
							
								
									
										
										
										
											2012-01-30 12:34:46 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  Vector actual_e = boost::dynamic_pointer_cast<NoiseModelFactor>(factor)->unwhitenedError(cfg);
							 | 
						
					
						
							
								
									
										
										
										
											2016-04-16 05:30:54 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  CHECK(assert_equal(0.1*Vector::Ones(2),actual_e));
							 | 
						
					
						
							
								
									
										
										
										
											2010-01-18 13:38:53 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // error = 0.5 * [1 1] * [1;1] = 1
							 | 
						
					
						
							
								
									
										
										
										
											2012-01-30 05:12:58 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  double expected = 1.0;
							 | 
						
					
						
							
								
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // calculate the error from the factor "f1"
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  double actual = factor->error(cfg);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  DOUBLES_EQUAL(expected,actual,0.00000001);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								}
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2010-01-27 12:39:35 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/* ************************************************************************* */
							 | 
						
					
						
							
								
									
										
										
										
											2009-11-13 00:47:12 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								TEST( NonlinearFactor, linearize_f1 )
							 | 
						
					
						
							
								
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								{
							 | 
						
					
						
							
								
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  Values c = createNoisyValues();
							 | 
						
					
						
							
								
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // Grab a non-linear factor
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  NonlinearFactorGraph nfg = createNonlinearFactorGraph();
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  NonlinearFactorGraph::sharedFactor nlf = nfg[0];
							 | 
						
					
						
							
								
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // We linearize at noisy config from SmallExample
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  GaussianFactor::shared_ptr actual = nlf->linearize(c);
							 | 
						
					
						
							
								
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  GaussianFactorGraph lfg = createGaussianFactorGraph();
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  GaussianFactor::shared_ptr expected = lfg[0];
							 | 
						
					
						
							
								
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2010-01-10 21:54:34 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  CHECK(assert_equal(*expected,*actual));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // The error |A*dx-b| approximates (h(x0+dx)-z) = -error_vector
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // Hence i.e., b = approximates z-h(x0) = error_vector(x0)
							 | 
						
					
						
							
								
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  //CHECK(assert_equal(nlf->error_vector(c),actual->get_b()));
							 | 
						
					
						
							
								
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								}
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2010-01-27 12:39:35 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/* ************************************************************************* */
							 | 
						
					
						
							
								
									
										
										
										
											2009-11-13 00:47:12 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								TEST( NonlinearFactor, linearize_f2 )
							 | 
						
					
						
							
								
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								{
							 | 
						
					
						
							
								
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  Values c = createNoisyValues();
							 | 
						
					
						
							
								
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // Grab a non-linear factor
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  NonlinearFactorGraph nfg = createNonlinearFactorGraph();
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  NonlinearFactorGraph::sharedFactor nlf = nfg[1];
							 | 
						
					
						
							
								
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // We linearize at noisy config from SmallExample
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  GaussianFactor::shared_ptr actual = nlf->linearize(c);
							 | 
						
					
						
							
								
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  GaussianFactorGraph lfg = createGaussianFactorGraph();
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  GaussianFactor::shared_ptr expected = lfg[1];
							 | 
						
					
						
							
								
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2010-01-27 12:39:35 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  CHECK(assert_equal(*expected,*actual));
							 | 
						
					
						
							
								
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								}
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2010-01-27 12:39:35 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/* ************************************************************************* */
							 | 
						
					
						
							
								
									
										
										
										
											2009-11-13 00:47:12 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								TEST( NonlinearFactor, linearize_f3 )
							 | 
						
					
						
							
								
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								{
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // Grab a non-linear factor
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  NonlinearFactorGraph nfg = createNonlinearFactorGraph();
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  NonlinearFactorGraph::sharedFactor nlf = nfg[2];
							 | 
						
					
						
							
								
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // We linearize at noisy config from SmallExample
							 | 
						
					
						
							
								
									
										
										
										
											2012-02-03 00:16:46 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  Values c = createNoisyValues();
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  GaussianFactor::shared_ptr actual = nlf->linearize(c);
							 | 
						
					
						
							
								
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  GaussianFactorGraph lfg = createGaussianFactorGraph();
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  GaussianFactor::shared_ptr expected = lfg[2];
							 | 
						
					
						
							
								
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2010-01-27 12:39:35 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  CHECK(assert_equal(*expected,*actual));
							 | 
						
					
						
							
								
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								}
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2010-01-27 12:39:35 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/* ************************************************************************* */
							 | 
						
					
						
							
								
									
										
										
										
											2009-11-13 00:47:12 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								TEST( NonlinearFactor, linearize_f4 )
							 | 
						
					
						
							
								
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								{
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // Grab a non-linear factor
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  NonlinearFactorGraph nfg = createNonlinearFactorGraph();
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  NonlinearFactorGraph::sharedFactor nlf = nfg[3];
							 | 
						
					
						
							
								
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // We linearize at noisy config from SmallExample
							 | 
						
					
						
							
								
									
										
										
										
											2012-02-03 00:16:46 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  Values c = createNoisyValues();
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  GaussianFactor::shared_ptr actual = nlf->linearize(c);
							 | 
						
					
						
							
								
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  GaussianFactorGraph lfg = createGaussianFactorGraph();
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  GaussianFactor::shared_ptr expected = lfg[3];
							 | 
						
					
						
							
								
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2010-01-27 12:39:35 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  CHECK(assert_equal(*expected,*actual));
							 | 
						
					
						
							
								
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								}
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/* ************************************************************************* */
							 | 
						
					
						
							
								
									
										
										
										
											2009-11-13 00:47:12 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								TEST( NonlinearFactor, size )
							 | 
						
					
						
							
								
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								{
							 | 
						
					
						
							
								
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  // create a non linear factor graph
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  NonlinearFactorGraph fg = createNonlinearFactorGraph();
							 | 
						
					
						
							
								
									
										
										
										
											2012-01-30 05:12:58 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  // create a values structure for the non linear factor graph
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  Values cfg = createNoisyValues();
							 | 
						
					
						
							
								
									
										
										
										
											2012-01-30 05:12:58 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  // get some factors from the graph
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  NonlinearFactorGraph::sharedFactor factor1 = fg[0], factor2 = fg[1],
							 | 
						
					
						
							
								
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								      factor3 = fg[2];
							 | 
						
					
						
							
								
									
										
										
										
											2012-01-30 05:12:58 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  CHECK(factor1->size() == 1);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  CHECK(factor2->size() == 2);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  CHECK(factor3->size() == 2);
							 | 
						
					
						
							
								
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								}
							 | 
						
					
						
							
								
									
										
										
										
											2009-12-08 07:17:03 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2010-01-29 01:21:24 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/* ************************************************************************* */
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								TEST( NonlinearFactor, linearize_constraint1 )
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								{
							 | 
						
					
						
							
								
									
										
										
										
											2014-10-12 05:06:57 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  SharedDiagonal constraint = noiseModel::Constrained::MixedSigmas(Vector2(0.2,0));
							 | 
						
					
						
							
								
									
										
										
										
											2010-01-29 01:21:24 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  Point2 mu(1., -1.);
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  NonlinearFactorGraph::sharedFactor f0(new simulated2D::Prior(mu, constraint, X(1)));
							 | 
						
					
						
							
								
									
										
										
										
											2010-01-29 01:21:24 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  Values config;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  config.insert(X(1), Point2(1.0, 2.0));
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  GaussianFactor::shared_ptr actual = f0->linearize(config);
							 | 
						
					
						
							
								
									
										
										
										
											2010-01-29 01:21:24 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  // create expected
							 | 
						
					
						
							
								
									
										
										
										
											2014-10-12 05:06:57 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  Vector2 b(0., -3.);
							 | 
						
					
						
							
								
									
										
										
										
											2014-11-23 08:35:27 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  JacobianFactor expected(X(1), (Matrix(2, 2) << 5.0, 0.0, 0.0, 1.0).finished(), b,
							 | 
						
					
						
							
								
									
										
										
										
											2014-10-12 05:06:57 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    noiseModel::Constrained::MixedSigmas(Vector2(1,0)));
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  CHECK(assert_equal((const GaussianFactor&)expected, *actual));
							 | 
						
					
						
							
								
									
										
										
										
											2010-01-29 01:21:24 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								}
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/* ************************************************************************* */
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								TEST( NonlinearFactor, linearize_constraint2 )
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								{
							 | 
						
					
						
							
								
									
										
										
										
											2014-10-12 05:06:57 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  SharedDiagonal constraint = noiseModel::Constrained::MixedSigmas(Vector2(0.2,0));
							 | 
						
					
						
							
								
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  Point2 z3(1.,-1.);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  simulated2D::Measurement f0(z3, constraint, X(1),L(1));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  Values config;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  config.insert(X(1), Point2(1.0, 2.0));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  config.insert(L(1), Point2(5.0, 4.0));
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  GaussianFactor::shared_ptr actual = f0.linearize(config);
							 | 
						
					
						
							
								
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // create expected
							 | 
						
					
						
							
								
									
										
										
										
											2014-10-12 05:06:57 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  Matrix2 A; A << 5.0, 0.0, 0.0, 1.0;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  Vector2 b(-15., -3.);
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-07 02:04:37 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  JacobianFactor expected(X(1), -1*A, L(1), A, b,
							 | 
						
					
						
							
								
									
										
										
										
											2014-10-12 05:06:57 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    noiseModel::Constrained::MixedSigmas(Vector2(1,0)));
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  CHECK(assert_equal((const GaussianFactor&)expected, *actual));
							 | 
						
					
						
							
								
									
										
										
										
											2010-01-29 01:21:24 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								}
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2011-10-26 10:07:35 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								/* ************************************************************************* */
							 | 
						
					
						
							
								
									
										
										
										
											2014-11-04 22:44:20 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								class TestFactor4 : public NoiseModelFactor4<double, double, double, double> {
							 | 
						
					
						
							
								
									
										
										
										
											2011-10-26 10:07:35 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								public:
							 | 
						
					
						
							
								
									
										
										
										
											2014-11-04 22:44:20 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  typedef NoiseModelFactor4<double, double, double, double> Base;
							 | 
						
					
						
							
								
									
										
										
										
											2014-11-23 08:35:27 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  TestFactor4() : Base(noiseModel::Diagonal::Sigmas((Vector(1) << 2.0).finished()), X(1), X(2), X(3), X(4)) {}
							 | 
						
					
						
							
								
									
										
										
										
											2011-10-26 10:07:35 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  virtual Vector
							 | 
						
					
						
							
								
									
										
										
										
											2014-11-04 22:44:20 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    evaluateError(const double& x1, const double& x2, const double& x3, const double& x4,
							 | 
						
					
						
							
								
									
										
										
										
											2011-10-26 10:07:35 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								        boost::optional<Matrix&> H1 = boost::none,
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								        boost::optional<Matrix&> H2 = boost::none,
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								        boost::optional<Matrix&> H3 = boost::none,
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								        boost::optional<Matrix&> H4 = boost::none) const {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    if(H1) {
							 | 
						
					
						
							
								
									
										
										
										
											2014-11-23 08:35:27 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								      *H1 = (Matrix(1, 1) << 1.0).finished();
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      *H2 = (Matrix(1, 1) << 2.0).finished();
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      *H3 = (Matrix(1, 1) << 3.0).finished();
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      *H4 = (Matrix(1, 1) << 4.0).finished();
							 | 
						
					
						
							
								
									
										
										
										
											2011-10-26 10:07:35 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    return (Vector(1) << x1 + x2 + x3 + x4).finished();
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  }
							 | 
						
					
						
							
								
									
										
										
										
											2012-05-22 04:54:40 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  virtual gtsam::NonlinearFactor::shared_ptr clone() const {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    return boost::static_pointer_cast<gtsam::NonlinearFactor>(
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								        gtsam::NonlinearFactor::shared_ptr(new TestFactor4(*this))); }
							 | 
						
					
						
							
								
									
										
										
										
											2011-10-26 10:07:35 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								};
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/* ************************************ */
							 | 
						
					
						
							
								
									
										
										
										
											2012-02-21 05:52:47 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								TEST(NonlinearFactor, NoiseModelFactor4) {
							 | 
						
					
						
							
								
									
										
										
										
											2011-10-26 10:07:35 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  TestFactor4 tf;
							 | 
						
					
						
							
								
									
										
										
										
											2012-02-03 00:16:46 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  Values tv;
							 | 
						
					
						
							
								
									
										
										
										
											2014-11-04 22:44:20 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  tv.insert(X(1), double((1.0)));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  tv.insert(X(2), double((2.0)));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  tv.insert(X(3), double((3.0)));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  tv.insert(X(4), double((4.0)));
							 | 
						
					
						
							
								
									
										
										
										
											2014-11-23 08:35:27 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  EXPECT(assert_equal((Vector(1) << 10.0).finished(), tf.unwhitenedError(tv)));
							 | 
						
					
						
							
								
									
										
										
										
											2011-10-26 10:07:35 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  DOUBLES_EQUAL(25.0/2.0, tf.error(tv), 1e-9);
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  JacobianFactor jf(*boost::dynamic_pointer_cast<JacobianFactor>(tf.linearize(tv)));
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-12 02:18:06 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  LONGS_EQUAL((long)X(1), (long)jf.keys()[0]);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  LONGS_EQUAL((long)X(2), (long)jf.keys()[1]);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  LONGS_EQUAL((long)X(3), (long)jf.keys()[2]);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  LONGS_EQUAL((long)X(4), (long)jf.keys()[3]);
							 | 
						
					
						
							
								
									
										
										
										
											2014-11-23 08:35:27 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  EXPECT(assert_equal((Matrix)(Matrix(1, 1) << 0.5).finished(), jf.getA(jf.begin())));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  EXPECT(assert_equal((Matrix)(Matrix(1, 1) << 1.0).finished(), jf.getA(jf.begin()+1)));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  EXPECT(assert_equal((Matrix)(Matrix(1, 1) << 1.5).finished(), jf.getA(jf.begin()+2)));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  EXPECT(assert_equal((Matrix)(Matrix(1, 1) << 2.0).finished(), jf.getA(jf.begin()+3)));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  EXPECT(assert_equal((Vector)(Vector(1) << -5.0).finished(), jf.getb()));
							 | 
						
					
						
							
								
									
										
										
										
											2011-10-26 10:07:35 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								}
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/* ************************************************************************* */
							 | 
						
					
						
							
								
									
										
										
										
											2014-11-04 22:44:20 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								class TestFactor5 : public NoiseModelFactor5<double, double, double, double, double> {
							 | 
						
					
						
							
								
									
										
										
										
											2011-10-26 10:07:35 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								public:
							 | 
						
					
						
							
								
									
										
										
										
											2014-11-04 22:44:20 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  typedef NoiseModelFactor5<double, double, double, double, double> Base;
							 | 
						
					
						
							
								
									
										
										
										
											2014-11-23 08:35:27 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  TestFactor5() : Base(noiseModel::Diagonal::Sigmas((Vector(1) << 2.0).finished()), X(1), X(2), X(3), X(4), X(5)) {}
							 | 
						
					
						
							
								
									
										
										
										
											2011-10-26 10:07:35 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  virtual Vector
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    evaluateError(const X1& x1, const X2& x2, const X3& x3, const X4& x4, const X5& x5,
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								        boost::optional<Matrix&> H1 = boost::none,
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								        boost::optional<Matrix&> H2 = boost::none,
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								        boost::optional<Matrix&> H3 = boost::none,
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								        boost::optional<Matrix&> H4 = boost::none,
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								        boost::optional<Matrix&> H5 = boost::none) const {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    if(H1) {
							 | 
						
					
						
							
								
									
										
										
										
											2014-11-23 08:35:27 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								      *H1 = (Matrix(1, 1) << 1.0).finished();
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      *H2 = (Matrix(1, 1) << 2.0).finished();
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      *H3 = (Matrix(1, 1) << 3.0).finished();
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      *H4 = (Matrix(1, 1) << 4.0).finished();
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      *H5 = (Matrix(1, 1) << 5.0).finished();
							 | 
						
					
						
							
								
									
										
										
										
											2011-10-26 10:07:35 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    return (Vector(1) << x1 + x2 + x3 + x4 + x5).finished();
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								};
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/* ************************************ */
							 | 
						
					
						
							
								
									
										
										
										
											2012-02-21 05:52:47 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								TEST(NonlinearFactor, NoiseModelFactor5) {
							 | 
						
					
						
							
								
									
										
										
										
											2011-10-26 10:07:35 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  TestFactor5 tf;
							 | 
						
					
						
							
								
									
										
										
										
											2012-02-03 00:16:46 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  Values tv;
							 | 
						
					
						
							
								
									
										
										
										
											2014-11-04 22:44:20 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  tv.insert(X(1), double((1.0)));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  tv.insert(X(2), double((2.0)));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  tv.insert(X(3), double((3.0)));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  tv.insert(X(4), double((4.0)));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  tv.insert(X(5), double((5.0)));
							 | 
						
					
						
							
								
									
										
										
										
											2014-11-23 08:35:27 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  EXPECT(assert_equal((Vector(1) << 15.0).finished(), tf.unwhitenedError(tv)));
							 | 
						
					
						
							
								
									
										
										
										
											2011-10-26 10:07:35 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  DOUBLES_EQUAL(56.25/2.0, tf.error(tv), 1e-9);
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  JacobianFactor jf(*boost::dynamic_pointer_cast<JacobianFactor>(tf.linearize(tv)));
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-12 02:18:06 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  LONGS_EQUAL((long)X(1), (long)jf.keys()[0]);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  LONGS_EQUAL((long)X(2), (long)jf.keys()[1]);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  LONGS_EQUAL((long)X(3), (long)jf.keys()[2]);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  LONGS_EQUAL((long)X(4), (long)jf.keys()[3]);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  LONGS_EQUAL((long)X(5), (long)jf.keys()[4]);
							 | 
						
					
						
							
								
									
										
										
										
											2014-11-23 08:35:27 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  EXPECT(assert_equal((Matrix)(Matrix(1, 1) << 0.5).finished(), jf.getA(jf.begin())));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  EXPECT(assert_equal((Matrix)(Matrix(1, 1) << 1.0).finished(), jf.getA(jf.begin()+1)));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  EXPECT(assert_equal((Matrix)(Matrix(1, 1) << 1.5).finished(), jf.getA(jf.begin()+2)));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  EXPECT(assert_equal((Matrix)(Matrix(1, 1) << 2.0).finished(), jf.getA(jf.begin()+3)));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  EXPECT(assert_equal((Matrix)(Matrix(1, 1) << 2.5).finished(), jf.getA(jf.begin()+4)));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  EXPECT(assert_equal((Vector)(Vector(1) << -7.5).finished(), jf.getb()));
							 | 
						
					
						
							
								
									
										
										
										
											2011-10-26 10:07:35 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								}
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/* ************************************************************************* */
							 | 
						
					
						
							
								
									
										
										
										
											2014-11-04 22:44:20 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								class TestFactor6 : public NoiseModelFactor6<double, double, double, double, double, double> {
							 | 
						
					
						
							
								
									
										
										
										
											2011-10-26 10:07:35 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								public:
							 | 
						
					
						
							
								
									
										
										
										
											2014-11-04 22:44:20 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  typedef NoiseModelFactor6<double, double, double, double, double, double> Base;
							 | 
						
					
						
							
								
									
										
										
										
											2014-11-23 08:35:27 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  TestFactor6() : Base(noiseModel::Diagonal::Sigmas((Vector(1) << 2.0).finished()), X(1), X(2), X(3), X(4), X(5), X(6)) {}
							 | 
						
					
						
							
								
									
										
										
										
											2011-10-26 10:07:35 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  virtual Vector
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    evaluateError(const X1& x1, const X2& x2, const X3& x3, const X4& x4, const X5& x5, const X6& x6,
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								        boost::optional<Matrix&> H1 = boost::none,
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								        boost::optional<Matrix&> H2 = boost::none,
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								        boost::optional<Matrix&> H3 = boost::none,
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								        boost::optional<Matrix&> H4 = boost::none,
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								        boost::optional<Matrix&> H5 = boost::none,
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								        boost::optional<Matrix&> H6 = boost::none) const {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    if(H1) {
							 | 
						
					
						
							
								
									
										
										
										
											2014-11-23 08:35:27 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								      *H1 = (Matrix(1, 1) << 1.0).finished();
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      *H2 = (Matrix(1, 1) << 2.0).finished();
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      *H3 = (Matrix(1, 1) << 3.0).finished();
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      *H4 = (Matrix(1, 1) << 4.0).finished();
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      *H5 = (Matrix(1, 1) << 5.0).finished();
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      *H6 = (Matrix(1, 1) << 6.0).finished();
							 | 
						
					
						
							
								
									
										
										
										
											2011-10-26 10:07:35 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    return (Vector(1) << x1 + x2 + x3 + x4 + x5 + x6).finished();
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  }
							 | 
						
					
						
							
								
									
										
										
										
											2012-05-22 04:54:40 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2011-10-26 10:07:35 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								};
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/* ************************************ */
							 | 
						
					
						
							
								
									
										
										
										
											2012-02-21 05:52:47 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								TEST(NonlinearFactor, NoiseModelFactor6) {
							 | 
						
					
						
							
								
									
										
										
										
											2011-10-26 10:07:35 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  TestFactor6 tf;
							 | 
						
					
						
							
								
									
										
										
										
											2012-02-03 00:16:46 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  Values tv;
							 | 
						
					
						
							
								
									
										
										
										
											2014-11-04 22:44:20 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  tv.insert(X(1), double((1.0)));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  tv.insert(X(2), double((2.0)));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  tv.insert(X(3), double((3.0)));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  tv.insert(X(4), double((4.0)));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  tv.insert(X(5), double((5.0)));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  tv.insert(X(6), double((6.0)));
							 | 
						
					
						
							
								
									
										
										
										
											2014-11-23 08:35:27 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  EXPECT(assert_equal((Vector(1) << 21.0).finished(), tf.unwhitenedError(tv)));
							 | 
						
					
						
							
								
									
										
										
										
											2011-10-26 10:07:35 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  DOUBLES_EQUAL(110.25/2.0, tf.error(tv), 1e-9);
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  JacobianFactor jf(*boost::dynamic_pointer_cast<JacobianFactor>(tf.linearize(tv)));
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-12 02:18:06 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  LONGS_EQUAL((long)X(1), (long)jf.keys()[0]);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  LONGS_EQUAL((long)X(2), (long)jf.keys()[1]);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  LONGS_EQUAL((long)X(3), (long)jf.keys()[2]);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  LONGS_EQUAL((long)X(4), (long)jf.keys()[3]);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  LONGS_EQUAL((long)X(5), (long)jf.keys()[4]);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  LONGS_EQUAL((long)X(6), (long)jf.keys()[5]);
							 | 
						
					
						
							
								
									
										
										
										
											2014-11-23 08:35:27 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  EXPECT(assert_equal((Matrix)(Matrix(1, 1) << 0.5).finished(), jf.getA(jf.begin())));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  EXPECT(assert_equal((Matrix)(Matrix(1, 1) << 1.0).finished(), jf.getA(jf.begin()+1)));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  EXPECT(assert_equal((Matrix)(Matrix(1, 1) << 1.5).finished(), jf.getA(jf.begin()+2)));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  EXPECT(assert_equal((Matrix)(Matrix(1, 1) << 2.0).finished(), jf.getA(jf.begin()+3)));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  EXPECT(assert_equal((Matrix)(Matrix(1, 1) << 2.5).finished(), jf.getA(jf.begin()+4)));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  EXPECT(assert_equal((Matrix)(Matrix(1, 1) << 3.0).finished(), jf.getA(jf.begin()+5)));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  EXPECT(assert_equal((Vector)(Vector(1) << -10.5).finished(), jf.getb()));
							 | 
						
					
						
							
								
									
										
										
										
											2011-10-26 10:07:35 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								}
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2012-05-22 04:54:40 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								/* ************************************************************************* */
							 | 
						
					
						
							
								
									
										
										
										
											2012-05-22 04:54:42 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								TEST( NonlinearFactor, clone_rekey )
							 | 
						
					
						
							
								
									
										
										
										
											2012-05-22 04:54:40 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								{
							 | 
						
					
						
							
								
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  shared_nlf init(new TestFactor4());
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  EXPECT_LONGS_EQUAL((long)X(1), (long)init->keys()[0]);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  EXPECT_LONGS_EQUAL((long)X(2), (long)init->keys()[1]);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  EXPECT_LONGS_EQUAL((long)X(3), (long)init->keys()[2]);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  EXPECT_LONGS_EQUAL((long)X(4), (long)init->keys()[3]);
							 | 
						
					
						
							
								
									
										
										
										
											2012-05-22 04:54:40 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2012-05-22 04:54:42 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  // Standard clone
							 | 
						
					
						
							
								
									
										
										
										
											2012-05-22 04:54:40 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  shared_nlf actClone = init->clone();
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  EXPECT(actClone.get() != init.get()); // Ensure different pointers
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  EXPECT(assert_equal(*init, *actClone));
							 | 
						
					
						
							
								
									
										
										
										
											2012-05-22 04:54:42 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // Re-key factor - clones with different keys
							 | 
						
					
						
							
								
									
										
										
										
											2018-11-09 06:18:47 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  KeyVector new_keys {X(5),X(6),X(7),X(8)};
							 | 
						
					
						
							
								
									
										
										
										
											2012-05-22 04:54:42 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  shared_nlf actRekey = init->rekey(new_keys);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  EXPECT(actRekey.get() != init.get()); // Ensure different pointers
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // Ensure init is unchanged
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  EXPECT_LONGS_EQUAL((long)X(1), (long)init->keys()[0]);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  EXPECT_LONGS_EQUAL((long)X(2), (long)init->keys()[1]);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  EXPECT_LONGS_EQUAL((long)X(3), (long)init->keys()[2]);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  EXPECT_LONGS_EQUAL((long)X(4), (long)init->keys()[3]);
							 | 
						
					
						
							
								
									
										
										
										
											2012-05-22 04:54:42 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // Check new keys
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  EXPECT_LONGS_EQUAL((long)X(5), (long)actRekey->keys()[0]);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  EXPECT_LONGS_EQUAL((long)X(6), (long)actRekey->keys()[1]);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  EXPECT_LONGS_EQUAL((long)X(7), (long)actRekey->keys()[2]);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  EXPECT_LONGS_EQUAL((long)X(8), (long)actRekey->keys()[3]);
							 | 
						
					
						
							
								
									
										
										
										
											2012-05-22 04:54:40 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								}
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/* ************************************************************************* */
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								int main() { TestResult tr; return TestRegistry::runAllTests(tr);}
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/* ************************************************************************* */
							 |