2014-11-27 23:45:23 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/* ----------------------------------------------------------------------------
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 * GTSAM Copyright 2010, Georgia Tech Research Corporation,
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 * Atlanta, Georgia 30332-0415
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 * All Rights Reserved
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 * See LICENSE for the license information
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 * -------------------------------------------------------------------------- */
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/**
							 | 
						
					
						
							
								
									
										
										
										
											2014-12-13 14:04:08 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 *  @file   testLinearEquality.cpp
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 *  @brief  Unit tests for LinearEquality
							 | 
						
					
						
							
								
									
										
										
										
											2015-02-25 11:25:26 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								 *  @author Duy-Nguyen Ta
							 | 
						
					
						
							
								
									
										
										
										
											2014-11-27 23:45:23 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 **/
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2014-12-13 14:04:08 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								#include <gtsam_unstable/linear/LinearEquality.h>
							 | 
						
					
						
							
								
									
										
										
										
											2014-11-27 23:45:23 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								#include <gtsam/base/TestableAssertions.h>
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								#include <gtsam/linear/HessianFactor.h>
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								#include <gtsam/linear/VectorValues.h>
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								#include <CppUnitLite/TestHarness.h>
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								#include <boost/assign/std/vector.hpp>
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								#include <boost/assign/list_of.hpp>
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								using namespace std;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								using namespace gtsam;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								using namespace boost::assign;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2016-06-14 10:58:36 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								GTSAM_CONCEPT_TESTABLE_INST (LinearEquality)
							 | 
						
					
						
							
								
									
										
										
										
											2014-12-09 19:13:01 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2014-11-27 23:45:23 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								namespace {
							 | 
						
					
						
							
								
									
										
										
										
											2016-06-14 10:58:36 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								namespace simple {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								// Terms we'll use
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								const vector<pair<Key, Matrix> > terms = list_of < pair<Key, Matrix>
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    > (make_pair(5, Matrix3::Identity()))(
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								        make_pair(10, 2 * Matrix3::Identity()))(
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								        make_pair(15, 3 * Matrix3::Identity()));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								// RHS and sigmas
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								const Vector b = (Vector(3) << 1., 2., 3.).finished();
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								const SharedDiagonal noise = noiseModel::Constrained::All(3);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								}
							 | 
						
					
						
							
								
									
										
										
										
											2014-11-27 23:45:23 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								}
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/* ************************************************************************* */
							 | 
						
					
						
							
								
									
										
										
										
											2014-12-13 14:04:08 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								TEST(LinearEquality, constructors_and_accessors)
							 | 
						
					
						
							
								
									
										
										
										
											2014-11-27 23:45:23 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								{
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  using namespace simple;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // Test for using different numbers of terms
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    // One term constructor
							 | 
						
					
						
							
								
									
										
										
										
											2014-12-13 14:04:08 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    LinearEquality expected(
							 | 
						
					
						
							
								
									
										
										
										
											2016-06-14 10:58:36 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								        boost::make_iterator_range(terms.begin(), terms.begin() + 1), b, 0);
							 | 
						
					
						
							
								
									
										
										
										
											2014-12-13 14:04:08 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    LinearEquality actual(terms[0].first, terms[0].second, b, 0);
							 | 
						
					
						
							
								
									
										
										
										
											2014-11-27 23:45:23 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    EXPECT(assert_equal(expected, actual));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    LONGS_EQUAL((long)terms[0].first, (long)actual.keys().back());
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    EXPECT(assert_equal(terms[0].second, actual.getA(actual.end() - 1)));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    EXPECT(assert_equal(b, expected.getb()));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    EXPECT(assert_equal(b, actual.getb()));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    EXPECT(assert_equal(*noise, *actual.get_model()));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    // Two term constructor
							 | 
						
					
						
							
								
									
										
										
										
											2014-12-13 14:04:08 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    LinearEquality expected(
							 | 
						
					
						
							
								
									
										
										
										
											2016-06-14 10:58:36 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								        boost::make_iterator_range(terms.begin(), terms.begin() + 2), b, 0);
							 | 
						
					
						
							
								
									
										
										
										
											2014-12-13 14:04:08 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    LinearEquality actual(terms[0].first, terms[0].second,
							 | 
						
					
						
							
								
									
										
										
										
											2016-06-14 10:58:36 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								        terms[1].first, terms[1].second, b, 0);
							 | 
						
					
						
							
								
									
										
										
										
											2014-11-27 23:45:23 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    EXPECT(assert_equal(expected, actual));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    LONGS_EQUAL((long)terms[1].first, (long)actual.keys().back());
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    EXPECT(assert_equal(terms[1].second, actual.getA(actual.end() - 1)));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    EXPECT(assert_equal(b, expected.getb()));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    EXPECT(assert_equal(b, actual.getb()));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    EXPECT(assert_equal(*noise, *actual.get_model()));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    // Three term constructor
							 | 
						
					
						
							
								
									
										
										
										
											2014-12-13 14:04:08 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    LinearEquality expected(
							 | 
						
					
						
							
								
									
										
										
										
											2016-06-14 10:58:36 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								        boost::make_iterator_range(terms.begin(), terms.begin() + 3), b, 0);
							 | 
						
					
						
							
								
									
										
										
										
											2014-12-13 14:04:08 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    LinearEquality actual(terms[0].first, terms[0].second,
							 | 
						
					
						
							
								
									
										
										
										
											2016-06-14 10:58:36 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								        terms[1].first, terms[1].second, terms[2].first, terms[2].second, b, 0);
							 | 
						
					
						
							
								
									
										
										
										
											2014-11-27 23:45:23 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    EXPECT(assert_equal(expected, actual));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    LONGS_EQUAL((long)terms[2].first, (long)actual.keys().back());
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    EXPECT(assert_equal(terms[2].second, actual.getA(actual.end() - 1)));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    EXPECT(assert_equal(b, expected.getb()));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    EXPECT(assert_equal(b, actual.getb()));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    EXPECT(assert_equal(*noise, *actual.get_model()));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								}
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/* ************************************************************************* */
							 | 
						
					
						
							
								
									
										
										
										
											2014-12-13 14:04:08 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								TEST(LinearEquality, Hessian_conversion) {
							 | 
						
					
						
							
								
									
										
										
										
											2014-11-27 23:45:23 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  HessianFactor hessian(0, (Matrix(4,4) <<
							 | 
						
					
						
							
								
									
										
										
										
											2016-06-14 10:58:36 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								          1.57, 2.695, -1.1, -2.35,
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								          2.695, 11.3125, -0.65, -10.225,
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								          -1.1, -0.65, 1, 0.5,
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								          -2.35, -10.225, 0.5, 9.25).finished(),
							 | 
						
					
						
							
								
									
										
										
										
											2014-12-13 06:23:31 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      (Vector(4) << -7.885, -28.5175, 2.75, 25.675).finished(),
							 | 
						
					
						
							
								
									
										
										
										
											2014-11-27 23:45:23 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      73.1725);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  try {
							 | 
						
					
						
							
								
									
										
										
										
											2014-12-13 14:04:08 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    LinearEquality actual(hessian);
							 | 
						
					
						
							
								
									
										
										
										
											2014-11-27 23:45:23 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    EXPECT(false);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  catch (const std::runtime_error& exception) {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    EXPECT(true);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								}
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/* ************************************************************************* */
							 | 
						
					
						
							
								
									
										
										
										
											2014-12-13 14:04:08 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								TEST(LinearEquality, error)
							 | 
						
					
						
							
								
									
										
										
										
											2014-11-27 23:45:23 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								{
							 | 
						
					
						
							
								
									
										
										
										
											2014-12-13 14:04:08 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  LinearEquality factor(simple::terms, simple::b, 0);
							 | 
						
					
						
							
								
									
										
										
										
											2014-11-27 23:45:23 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  VectorValues values;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  values.insert(5, Vector::Constant(3, 1.0));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  values.insert(10, Vector::Constant(3, 0.5));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  values.insert(15, Vector::Constant(3, 1.0/3.0));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  Vector expected_unwhitened(3); expected_unwhitened << 2.0, 1.0, 0.0;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  Vector actual_unwhitened = factor.unweighted_error(values);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  EXPECT(assert_equal(expected_unwhitened, actual_unwhitened));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // whitened is meaningless in constraints
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  Vector expected_whitened(3); expected_whitened = expected_unwhitened;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  Vector actual_whitened = factor.error_vector(values);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  EXPECT(assert_equal(expected_whitened, actual_whitened));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  double expected_error = 0.0;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  double actual_error = factor.error(values);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  DOUBLES_EQUAL(expected_error, actual_error, 1e-10);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								}
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/* ************************************************************************* */
							 | 
						
					
						
							
								
									
										
										
										
											2014-12-13 14:04:08 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								TEST(LinearEquality, matrices_NULL)
							 | 
						
					
						
							
								
									
										
										
										
											2014-11-27 23:45:23 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								{
							 | 
						
					
						
							
								
									
										
										
										
											2020-04-07 05:31:05 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  // Make sure everything works with nullptr noise model
							 | 
						
					
						
							
								
									
										
										
										
											2014-12-13 14:04:08 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  LinearEquality factor(simple::terms, simple::b, 0);
							 | 
						
					
						
							
								
									
										
										
										
											2014-11-27 23:45:23 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  Matrix AExpected(3, 9);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  AExpected << simple::terms[0].second, simple::terms[1].second, simple::terms[2].second;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  Vector rhsExpected = simple::b;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  Matrix augmentedJacobianExpected(3, 10);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  augmentedJacobianExpected << AExpected, rhsExpected;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // Whitened Jacobian
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  EXPECT(assert_equal(AExpected, factor.jacobian().first));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  EXPECT(assert_equal(rhsExpected, factor.jacobian().second));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  EXPECT(assert_equal(augmentedJacobianExpected, factor.augmentedJacobian()));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // Unwhitened Jacobian
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  EXPECT(assert_equal(AExpected, factor.jacobianUnweighted().first));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  EXPECT(assert_equal(rhsExpected, factor.jacobianUnweighted().second));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  EXPECT(assert_equal(augmentedJacobianExpected, factor.augmentedJacobianUnweighted()));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								}
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/* ************************************************************************* */
							 | 
						
					
						
							
								
									
										
										
										
											2014-12-13 14:04:08 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								TEST(LinearEquality, matrices)
							 | 
						
					
						
							
								
									
										
										
										
											2014-11-27 23:45:23 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								{
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // And now witgh a non-unit noise model
							 | 
						
					
						
							
								
									
										
										
										
											2014-12-13 14:04:08 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  LinearEquality factor(simple::terms, simple::b, 0);
							 | 
						
					
						
							
								
									
										
										
										
											2014-11-27 23:45:23 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  Matrix jacobianExpected(3, 9);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  jacobianExpected << simple::terms[0].second, simple::terms[1].second, simple::terms[2].second;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  Vector rhsExpected = simple::b;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  Matrix augmentedJacobianExpected(3, 10);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  augmentedJacobianExpected << jacobianExpected, rhsExpected;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  Matrix augmentedHessianExpected =
							 | 
						
					
						
							
								
									
										
										
										
											2016-06-14 10:58:36 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  augmentedJacobianExpected.transpose() * simple::noise->R().transpose()
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  * simple::noise->R() * augmentedJacobianExpected;
							 | 
						
					
						
							
								
									
										
										
										
											2014-11-27 23:45:23 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // Whitened Jacobian
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  EXPECT(assert_equal(jacobianExpected, factor.jacobian().first));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  EXPECT(assert_equal(rhsExpected, factor.jacobian().second));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  EXPECT(assert_equal(augmentedJacobianExpected, factor.augmentedJacobian()));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // Unwhitened Jacobian
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  EXPECT(assert_equal(jacobianExpected, factor.jacobianUnweighted().first));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  EXPECT(assert_equal(rhsExpected, factor.jacobianUnweighted().second));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  EXPECT(assert_equal(augmentedJacobianExpected, factor.augmentedJacobianUnweighted()));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								}
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/* ************************************************************************* */
							 | 
						
					
						
							
								
									
										
										
										
											2014-12-13 14:04:08 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								TEST(LinearEquality, operators )
							 | 
						
					
						
							
								
									
										
										
										
											2014-11-27 23:45:23 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								{
							 | 
						
					
						
							
								
									
										
										
										
											2016-04-12 03:11:29 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  Matrix I = I_2x2;
							 | 
						
					
						
							
								
									
										
										
										
											2014-12-13 06:23:31 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  Vector b = (Vector(2) << 0.2,-0.1).finished();
							 | 
						
					
						
							
								
									
										
										
										
											2014-12-13 14:04:08 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  LinearEquality lf(1, -I, 2, I, b, 0);
							 | 
						
					
						
							
								
									
										
										
										
											2014-11-27 23:45:23 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  VectorValues c;
							 | 
						
					
						
							
								
									
										
										
										
											2014-12-13 06:23:31 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  c.insert(1, (Vector(2) << 10.,20.).finished());
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  c.insert(2, (Vector(2) << 30.,60.).finished());
							 | 
						
					
						
							
								
									
										
										
										
											2014-11-27 23:45:23 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // test A*x
							 | 
						
					
						
							
								
									
										
										
										
											2014-12-13 06:23:31 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  Vector expectedE = (Vector(2) << 20.,40.).finished();
							 | 
						
					
						
							
								
									
										
										
										
											2014-11-27 23:45:23 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  Vector actualE = lf * c;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  EXPECT(assert_equal(expectedE, actualE));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // test A^e
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  VectorValues expectedX;
							 | 
						
					
						
							
								
									
										
										
										
											2014-12-13 06:23:31 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  expectedX.insert(1, (Vector(2) << -20.,-40.).finished());
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  expectedX.insert(2, (Vector(2) << 20., 40.).finished());
							 | 
						
					
						
							
								
									
										
										
										
											2014-11-27 23:45:23 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  VectorValues actualX = VectorValues::Zero(expectedX);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  lf.transposeMultiplyAdd(1.0, actualE, actualX);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  EXPECT(assert_equal(expectedX, actualX));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // test gradient at zero
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  Matrix A; Vector b2; boost::tie(A,b2) = lf.jacobian();
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  VectorValues expectedG;
							 | 
						
					
						
							
								
									
										
										
										
											2016-06-14 10:58:36 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  expectedG.insert(1, (Vector(2) << 0.2, -0.1).finished());
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  expectedG.insert(2, (Vector(2) << -0.2, 0.1).finished());
							 | 
						
					
						
							
								
									
										
										
										
											2014-11-27 23:45:23 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  VectorValues actualG = lf.gradientAtZero();
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  EXPECT(assert_equal(expectedG, actualG));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								}
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/* ************************************************************************* */
							 | 
						
					
						
							
								
									
										
										
										
											2014-12-13 14:04:08 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								TEST(LinearEquality, default_error )
							 | 
						
					
						
							
								
									
										
										
										
											2014-11-27 23:45:23 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								{
							 | 
						
					
						
							
								
									
										
										
										
											2014-12-13 14:04:08 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  LinearEquality f;
							 | 
						
					
						
							
								
									
										
										
										
											2014-11-27 23:45:23 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  double actual = f.error(VectorValues());
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  DOUBLES_EQUAL(0.0, actual, 1e-15);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								}
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								//* ************************************************************************* */
							 | 
						
					
						
							
								
									
										
										
										
											2014-12-13 14:04:08 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								TEST(LinearEquality, empty )
							 | 
						
					
						
							
								
									
										
										
										
											2014-11-27 23:45:23 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								{
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // create an empty factor
							 | 
						
					
						
							
								
									
										
										
										
											2014-12-13 14:04:08 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  LinearEquality f;
							 | 
						
					
						
							
								
									
										
										
										
											2014-11-27 23:45:23 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  EXPECT(f.empty());
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								}
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/* ************************************************************************* */
							 | 
						
					
						
							
								
									
										
										
										
											2016-06-14 10:58:36 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								int main() {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  TestResult tr;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  return TestRegistry::runAllTests(tr);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								}
							 | 
						
					
						
							
								
									
										
										
										
											2014-11-27 23:45:23 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/* ************************************************************************* */
							 |