2011-10-12 15:51:37 +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
* - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - */
2011-08-19 02:06:35 +08:00
/**
2012-03-17 04:55:21 +08:00
* @ file ISAM2 - impl . cpp
2011-08-19 02:06:35 +08:00
* @ brief Incremental update functionality ( ISAM2 ) for BayesTree , with fluid relinearization .
2012-06-03 03:05:38 +08:00
* @ author Michael Kaess
* @ author Richard Roberts
2011-08-19 02:06:35 +08:00
*/
2012-03-17 04:55:21 +08:00
# include <gtsam/nonlinear/ISAM2-impl.h>
2013-08-19 23:32:16 +08:00
# include <gtsam/inference/Symbol.h> // for selective linearization thresholds
2012-03-18 07:57:42 +08:00
# include <gtsam/base/debug.h>
2015-06-22 09:14:20 +08:00
# include <gtsam/config.h> // for GTSAM_USE_TBB
2012-05-23 06:52:17 +08:00
# include <functional>
2012-03-25 00:52:55 +08:00
# include <boost/range/adaptors.hpp>
2012-03-14 03:41:03 +08:00
2012-06-08 22:33:36 +08:00
using namespace std ;
2011-08-19 02:06:35 +08:00
namespace gtsam {
/* ************************************************************************* */
2012-03-17 04:55:21 +08:00
void ISAM2 : : Impl : : AddVariables (
2013-08-06 06:31:44 +08:00
const Values & newTheta , Values & theta , VectorValues & delta ,
2013-08-10 05:35:47 +08:00
VectorValues & deltaNewton , VectorValues & RgProd ,
const KeyFormatter & keyFormatter )
{
2011-08-19 02:06:35 +08:00
const bool debug = ISDEBUG ( " ISAM2 AddVariables " ) ;
theta . insert ( newTheta ) ;
if ( debug ) newTheta . print ( " The new variables are: " ) ;
2013-08-10 05:35:47 +08:00
// Add zeros into the VectorValues
delta . insert ( newTheta . zeroVectors ( ) ) ;
deltaNewton . insert ( newTheta . zeroVectors ( ) ) ;
RgProd . insert ( newTheta . zeroVectors ( ) ) ;
2011-08-19 02:06:35 +08:00
}
2013-11-19 03:23:09 +08:00
/* ************************************************************************* */
void ISAM2 : : Impl : : AddFactorsStep1 ( const NonlinearFactorGraph & newFactors , bool useUnusedSlots ,
2016-02-26 15:51:01 +08:00
NonlinearFactorGraph & nonlinearFactors , FactorIndices & newFactorIndices )
2013-11-19 03:23:09 +08:00
{
newFactorIndices . resize ( newFactors . size ( ) ) ;
if ( useUnusedSlots )
{
size_t globalFactorIndex = 0 ;
for ( size_t newFactorIndex = 0 ; newFactorIndex < newFactors . size ( ) ; + + newFactorIndex )
{
// Loop to find the next available factor slot
do
{
// If we need to add more factors than we have room for, resize nonlinearFactors,
// filling the new slots with NULL factors. Otherwise, check if the current
// factor in nonlinearFactors is already used, and if so, increase
// globalFactorIndex. If the current factor in nonlinearFactors is unused, break
// out of the loop and use the current slot.
if ( globalFactorIndex > = nonlinearFactors . size ( ) )
nonlinearFactors . resize ( nonlinearFactors . size ( ) + newFactors . size ( ) - newFactorIndex ) ;
else if ( nonlinearFactors [ globalFactorIndex ] )
+ + globalFactorIndex ;
else
break ;
} while ( true ) ;
// Use the current slot, updating nonlinearFactors and newFactorSlots.
nonlinearFactors [ globalFactorIndex ] = newFactors [ newFactorIndex ] ;
newFactorIndices [ newFactorIndex ] = globalFactorIndex ;
}
}
else
{
// We're not looking for unused slots, so just add the factors at the end.
for ( size_t i = 0 ; i < newFactors . size ( ) ; + + i )
newFactorIndices [ i ] = i + nonlinearFactors . size ( ) ;
nonlinearFactors . push_back ( newFactors ) ;
}
}
2012-07-01 03:17:54 +08:00
/* ************************************************************************* */
2015-06-21 09:38:25 +08:00
void ISAM2 : : Impl : : RemoveVariables ( const KeySet & unusedKeys , const FastVector < ISAM2 : : sharedClique > & roots ,
2013-08-06 06:31:44 +08:00
Values & theta , VariableIndex & variableIndex ,
VectorValues & delta , VectorValues & deltaNewton , VectorValues & RgProd ,
2015-06-21 09:38:25 +08:00
KeySet & replacedKeys , Base : : Nodes & nodes ,
KeySet & fixedVariables )
2013-08-10 05:35:47 +08:00
{
variableIndex . removeUnusedVariables ( unusedKeys . begin ( ) , unusedKeys . end ( ) ) ;
BOOST_FOREACH ( Key key , unusedKeys ) {
delta . erase ( key ) ;
deltaNewton . erase ( key ) ;
RgProd . erase ( key ) ;
replacedKeys . erase ( key ) ;
2013-08-16 01:23:52 +08:00
nodes . unsafe_erase ( key ) ;
2013-08-10 05:35:47 +08:00
theta . erase ( key ) ;
fixedVariables . erase ( key ) ;
}
2012-07-01 03:17:54 +08:00
}
2011-09-07 23:42:49 +08:00
/* ************************************************************************* */
2015-06-21 09:38:25 +08:00
KeySet ISAM2 : : Impl : : CheckRelinearizationFull ( const VectorValues & delta ,
2013-08-10 05:35:47 +08:00
const ISAM2Params : : RelinearizationThreshold & relinearizeThreshold )
{
2015-06-21 09:38:25 +08:00
KeySet relinKeys ;
2012-01-07 00:53:16 +08:00
2013-08-12 03:26:21 +08:00
if ( const double * threshold = boost : : get < double > ( & relinearizeThreshold ) )
2013-08-10 05:35:47 +08:00
{
BOOST_FOREACH ( const VectorValues : : KeyValuePair & key_delta , delta ) {
double maxDelta = key_delta . second . lpNorm < Eigen : : Infinity > ( ) ;
if ( maxDelta > = * threshold )
relinKeys . insert ( key_delta . first ) ;
2012-01-07 00:53:16 +08:00
}
2013-08-10 05:35:47 +08:00
}
2013-08-12 03:26:21 +08:00
else if ( const FastMap < char , Vector > * thresholds = boost : : get < FastMap < char , Vector > > ( & relinearizeThreshold ) )
2013-08-10 05:35:47 +08:00
{
BOOST_FOREACH ( const VectorValues : : KeyValuePair & key_delta , delta ) {
const Vector & threshold = thresholds - > find ( Symbol ( key_delta . first ) . chr ( ) ) - > second ;
if ( threshold . rows ( ) ! = key_delta . second . rows ( ) )
throw std : : invalid_argument ( " Relinearization threshold vector dimensionality for ' " + std : : string ( 1 , Symbol ( key_delta . first ) . chr ( ) ) + " ' passed into iSAM2 parameters does not match actual variable dimensionality. " ) ;
if ( ( key_delta . second . array ( ) . abs ( ) > threshold . array ( ) ) . any ( ) )
relinKeys . insert ( key_delta . first ) ;
2011-09-07 23:42:49 +08:00
}
}
2012-01-07 00:53:16 +08:00
2011-09-11 05:32:39 +08:00
return relinKeys ;
2011-09-07 23:42:49 +08:00
}
2012-06-29 04:46:53 +08:00
/* ************************************************************************* */
2015-06-21 09:38:25 +08:00
void CheckRelinearizationRecursiveDouble ( KeySet & relinKeys , double threshold ,
2013-08-10 05:35:47 +08:00
const VectorValues & delta , const ISAM2Clique : : shared_ptr & clique )
{
2012-06-29 04:46:53 +08:00
// Check the current clique for relinearization
bool relinearize = false ;
2013-08-10 05:35:47 +08:00
BOOST_FOREACH ( Key var , * clique - > conditional ( ) ) {
2012-06-29 04:46:53 +08:00
double maxDelta = delta [ var ] . lpNorm < Eigen : : Infinity > ( ) ;
if ( maxDelta > = threshold ) {
relinKeys . insert ( var ) ;
relinearize = true ;
}
}
// If this node was relinearized, also check its children
if ( relinearize ) {
2013-08-10 05:35:47 +08:00
BOOST_FOREACH ( const ISAM2Clique : : shared_ptr & child , clique - > children ) {
2012-06-29 04:46:53 +08:00
CheckRelinearizationRecursiveDouble ( relinKeys , threshold , delta , child ) ;
}
}
}
/* ************************************************************************* */
2015-06-21 09:38:25 +08:00
void CheckRelinearizationRecursiveMap ( KeySet & relinKeys , const FastMap < char , Vector > & thresholds ,
2013-08-10 05:35:47 +08:00
const VectorValues & delta ,
const ISAM2Clique : : shared_ptr & clique )
{
2012-06-29 04:46:53 +08:00
// Check the current clique for relinearization
bool relinearize = false ;
2013-08-10 05:35:47 +08:00
BOOST_FOREACH ( Key var , * clique - > conditional ( ) ) {
2012-06-29 04:46:53 +08:00
// Find the threshold for this variable type
2013-08-10 05:35:47 +08:00
const Vector & threshold = thresholds . find ( Symbol ( var ) . chr ( ) ) - > second ;
const Vector & deltaVar = delta [ var ] ;
2012-06-29 04:46:53 +08:00
// Verify the threshold vector matches the actual variable size
2013-08-10 05:35:47 +08:00
if ( threshold . rows ( ) ! = deltaVar . rows ( ) )
throw std : : invalid_argument ( " Relinearization threshold vector dimensionality for ' " + std : : string ( 1 , Symbol ( var ) . chr ( ) ) + " ' passed into iSAM2 parameters does not match actual variable dimensionality. " ) ;
2012-06-29 04:46:53 +08:00
// Check for relinearization
2013-08-10 05:35:47 +08:00
if ( ( deltaVar . array ( ) . abs ( ) > threshold . array ( ) ) . any ( ) ) {
2012-06-29 04:46:53 +08:00
relinKeys . insert ( var ) ;
relinearize = true ;
}
}
// If this node was relinearized, also check its children
if ( relinearize ) {
2013-08-10 05:35:47 +08:00
BOOST_FOREACH ( const ISAM2Clique : : shared_ptr & child , clique - > children ) {
CheckRelinearizationRecursiveMap ( relinKeys , thresholds , delta , child ) ;
2012-06-29 04:46:53 +08:00
}
}
}
/* ************************************************************************* */
2015-06-21 09:38:25 +08:00
KeySet ISAM2 : : Impl : : CheckRelinearizationPartial ( const FastVector < ISAM2 : : sharedClique > & roots ,
2013-08-10 05:35:47 +08:00
const VectorValues & delta ,
const ISAM2Params : : RelinearizationThreshold & relinearizeThreshold )
{
2015-06-21 09:38:25 +08:00
KeySet relinKeys ;
2013-08-10 05:35:47 +08:00
BOOST_FOREACH ( const ISAM2 : : sharedClique & root , roots ) {
if ( relinearizeThreshold . type ( ) = = typeid ( double ) )
2012-06-29 23:09:03 +08:00
CheckRelinearizationRecursiveDouble ( relinKeys , boost : : get < double > ( relinearizeThreshold ) , delta , root ) ;
2013-08-10 05:35:47 +08:00
else if ( relinearizeThreshold . type ( ) = = typeid ( FastMap < char , Vector > ) )
CheckRelinearizationRecursiveMap ( relinKeys , boost : : get < FastMap < char , Vector > > ( relinearizeThreshold ) , delta , root ) ;
2012-06-29 04:46:53 +08:00
}
return relinKeys ;
}
2011-09-28 04:24:39 +08:00
/* ************************************************************************* */
2015-06-21 09:38:25 +08:00
void ISAM2 : : Impl : : FindAll ( ISAM2Clique : : shared_ptr clique , KeySet & keys , const KeySet & markedMask )
2013-08-10 05:35:47 +08:00
{
2011-09-28 04:24:39 +08:00
static const bool debug = false ;
// does the separator contain any of the variables?
bool found = false ;
2013-08-10 05:35:47 +08:00
BOOST_FOREACH ( Key key , clique - > conditional ( ) - > parents ( ) ) {
if ( markedMask . exists ( key ) ) {
2011-09-28 04:24:39 +08:00
found = true ;
2013-08-10 05:35:47 +08:00
break ;
}
2011-09-28 04:24:39 +08:00
}
if ( found ) {
// then add this clique
2013-08-10 05:35:47 +08:00
keys . insert ( clique - > conditional ( ) - > beginFrontals ( ) , clique - > conditional ( ) - > endFrontals ( ) ) ;
2011-09-28 04:24:39 +08:00
if ( debug ) clique - > print ( " Key(s) marked in clique " ) ;
2013-08-10 05:35:47 +08:00
if ( debug ) cout < < " so marking key " < < clique - > conditional ( ) - > front ( ) < < endl ;
2011-09-28 04:24:39 +08:00
}
2013-08-10 05:35:47 +08:00
BOOST_FOREACH ( const ISAM2Clique : : shared_ptr & child , clique - > children ) {
2011-09-28 04:24:39 +08:00
FindAll ( child , keys , markedMask ) ;
}
}
/* ************************************************************************* */
2013-08-10 05:35:47 +08:00
void ISAM2 : : Impl : : ExpmapMasked ( Values & values , const VectorValues & delta ,
2015-06-21 09:38:25 +08:00
const KeySet & mask , boost : : optional < VectorValues & > invalidateIfDebug , const KeyFormatter & keyFormatter )
2013-08-10 05:35:47 +08:00
{
2011-09-28 04:24:39 +08:00
// If debugging, invalidate if requested, otherwise do not invalidate.
// Invalidating means setting expmapped entries to Inf, to trigger assertions
// if we try to re-use them.
# ifdef NDEBUG
2012-06-30 20:48:43 +08:00
invalidateIfDebug = boost : : none ;
2011-09-28 04:24:39 +08:00
# endif
2013-08-10 05:35:47 +08:00
assert ( values . size ( ) = = delta . size ( ) ) ;
2012-02-03 06:06:33 +08:00
Values : : iterator key_value ;
2013-08-10 05:35:47 +08:00
VectorValues : : const_iterator key_delta ;
2013-08-20 06:07:31 +08:00
# ifdef GTSAM_USE_TBB
for ( key_value = values . begin ( ) ; key_value ! = values . end ( ) ; + + key_value )
{
key_delta = delta . find ( key_value - > key ) ;
# else
2013-08-10 05:35:47 +08:00
for ( key_value = values . begin ( ) , key_delta = delta . begin ( ) ; key_value ! = values . end ( ) ; + + key_value , + + key_delta )
{
assert ( key_value - > key = = key_delta - > first ) ;
2013-08-20 06:07:31 +08:00
# endif
2013-08-10 05:35:47 +08:00
Key var = key_value - > key ;
2012-02-25 07:38:51 +08:00
assert ( delta [ var ] . size ( ) = = ( int ) key_value - > value . dim ( ) ) ;
2013-08-13 05:32:51 +08:00
assert ( delta [ var ] . allFinite ( ) ) ;
2013-08-10 05:35:47 +08:00
if ( mask . exists ( var ) ) {
2012-02-25 07:38:51 +08:00
Value * retracted = key_value - > value . retract_ ( delta [ var ] ) ;
key_value - > value = * retracted ;
2012-02-03 06:06:33 +08:00
retracted - > deallocate_ ( ) ;
if ( invalidateIfDebug )
( * invalidateIfDebug ) [ var ] . operator = ( Vector : : Constant ( delta [ var ] . rows ( ) , numeric_limits < double > : : infinity ( ) ) ) ; // Strange syntax to work with clang++ (bug in clang?)
}
}
2011-09-28 04:24:39 +08:00
}
2012-03-17 00:16:13 +08:00
/* ************************************************************************* */
namespace internal {
2013-08-06 06:31:44 +08:00
inline static void optimizeInPlace ( const boost : : shared_ptr < ISAM2Clique > & clique , VectorValues & result ) {
2012-03-17 00:16:13 +08:00
// parents are assumed to already be solved and available in result
2013-08-10 05:35:47 +08:00
result . update ( clique - > conditional ( ) - > solve ( result ) ) ;
2012-03-17 00:16:13 +08:00
// starting from the root, call optimize on each conditional
2013-08-10 05:35:47 +08:00
BOOST_FOREACH ( const boost : : shared_ptr < ISAM2Clique > & child , clique - > children )
2012-03-17 00:16:13 +08:00
optimizeInPlace ( child , result ) ;
}
}
2012-03-12 06:10:51 +08:00
/* ************************************************************************* */
2014-02-23 05:46:38 +08:00
size_t ISAM2 : : Impl : : UpdateGaussNewtonDelta ( const FastVector < ISAM2 : : sharedClique > & roots ,
2015-06-21 09:38:25 +08:00
const KeySet & replacedKeys , VectorValues & delta , double wildfireThreshold ) {
2012-03-12 06:10:51 +08:00
size_t lastBacksubVariableCount ;
if ( wildfireThreshold < = 0.0 ) {
// Threshold is zero or less, so do a full recalculation
2013-08-10 05:35:47 +08:00
BOOST_FOREACH ( const ISAM2 : : sharedClique & root , roots )
internal : : optimizeInPlace ( root , delta ) ;
2012-03-12 06:10:51 +08:00
lastBacksubVariableCount = delta . size ( ) ;
} else {
// Optimize with wildfire
2013-08-10 05:35:47 +08:00
lastBacksubVariableCount = 0 ;
BOOST_FOREACH ( const ISAM2 : : sharedClique & root , roots )
lastBacksubVariableCount + = optimizeWildfireNonRecursive (
root , wildfireThreshold , replacedKeys , delta ) ; // modifies delta
2012-03-12 06:10:51 +08:00
2013-05-21 01:26:53 +08:00
# ifdef GTSAM_EXTRA_CONSISTENCY_CHECKS
2012-06-30 09:45:21 +08:00
for ( size_t j = 0 ; j < delta . size ( ) ; + + j )
assert ( delta [ j ] . unaryExpr ( ptr_fun ( isfinite < double > ) ) . all ( ) ) ;
2012-03-12 06:10:51 +08:00
# endif
}
return lastBacksubVariableCount ;
}
2012-03-18 13:13:40 +08:00
/* ************************************************************************* */
namespace internal {
2015-06-21 09:38:25 +08:00
void updateRgProd ( const boost : : shared_ptr < ISAM2Clique > & clique , const KeySet & replacedKeys ,
2013-08-10 05:35:47 +08:00
const VectorValues & grad , VectorValues & RgProd , size_t & varsUpdated ) {
2012-03-19 22:32:37 +08:00
// Check if any frontal or separator keys were recalculated, if so, we need
// update deltas and recurse to children, but if not, we do not need to
// recurse further because of the running separator property.
bool anyReplaced = false ;
2013-08-10 05:35:47 +08:00
BOOST_FOREACH ( Key j , * clique - > conditional ( ) ) {
if ( replacedKeys . exists ( j ) ) {
2012-03-19 22:32:37 +08:00
anyReplaced = true ;
break ;
}
}
2012-03-18 13:13:40 +08:00
2012-03-19 22:32:37 +08:00
if ( anyReplaced ) {
// Update the current variable
// Get VectorValues slice corresponding to current variables
2013-08-16 01:21:20 +08:00
Vector gR = grad . vector ( FastVector < Key > ( clique - > conditional ( ) - > beginFrontals ( ) , clique - > conditional ( ) - > endFrontals ( ) ) ) ;
Vector gS = grad . vector ( FastVector < Key > ( clique - > conditional ( ) - > beginParents ( ) , clique - > conditional ( ) - > endParents ( ) ) ) ;
2012-03-18 13:13:40 +08:00
2012-03-19 22:32:37 +08:00
// Compute R*g and S*g for this clique
2013-08-10 05:35:47 +08:00
Vector RSgProd = clique - > conditional ( ) - > get_R ( ) * gR + clique - > conditional ( ) - > get_S ( ) * gS ;
2012-03-18 13:13:40 +08:00
2012-03-19 22:32:37 +08:00
// Write into RgProd vector
2013-08-10 05:35:47 +08:00
DenseIndex vectorPosition = 0 ;
BOOST_FOREACH ( Key frontal , clique - > conditional ( ) - > frontals ( ) ) {
Vector & RgProdValue = RgProd [ frontal ] ;
RgProdValue = RSgProd . segment ( vectorPosition , RgProdValue . size ( ) ) ;
vectorPosition + = RgProdValue . size ( ) ;
}
2012-03-18 13:13:40 +08:00
2012-03-19 22:32:37 +08:00
// Now solve the part of the Newton's method point for this clique (back-substitution)
2012-03-20 00:25:03 +08:00
//(*clique)->solveInPlace(deltaNewton);
2012-03-19 22:32:37 +08:00
2013-08-10 05:35:47 +08:00
varsUpdated + = clique - > conditional ( ) - > nrFrontals ( ) ;
2012-03-19 22:32:37 +08:00
// Recurse to children
2013-08-10 05:35:47 +08:00
BOOST_FOREACH ( const ISAM2Clique : : shared_ptr & child , clique - > children ) {
2014-02-23 05:46:38 +08:00
updateRgProd ( child , replacedKeys , grad , RgProd , varsUpdated ) ; }
2012-03-19 22:32:37 +08:00
}
2012-03-18 13:13:40 +08:00
}
}
/* ************************************************************************* */
2015-06-21 09:38:25 +08:00
size_t ISAM2 : : Impl : : UpdateRgProd ( const ISAM2 : : Roots & roots , const KeySet & replacedKeys ,
2014-02-23 05:46:38 +08:00
const VectorValues & gradAtZero , VectorValues & RgProd ) {
2012-03-18 13:13:40 +08:00
// Update variables
2012-03-19 22:32:37 +08:00
size_t varsUpdated = 0 ;
2014-02-23 05:46:38 +08:00
BOOST_FOREACH ( const ISAM2 : : sharedClique & root , roots ) {
internal : : updateRgProd ( root , replacedKeys , gradAtZero , RgProd , varsUpdated ) ;
2013-08-10 05:35:47 +08:00
}
2012-03-20 00:25:03 +08:00
2012-03-19 22:32:37 +08:00
return varsUpdated ;
2012-03-18 13:13:40 +08:00
}
2014-02-23 05:46:38 +08:00
/* ************************************************************************* */
VectorValues ISAM2 : : Impl : : ComputeGradientSearch ( const VectorValues & gradAtZero ,
const VectorValues & RgProd )
{
// Compute gradient squared-magnitude
const double gradientSqNorm = gradAtZero . dot ( gradAtZero ) ;
// Compute minimizing step size
double RgNormSq = RgProd . vector ( ) . squaredNorm ( ) ;
double step = - gradientSqNorm / RgNormSq ;
// Compute steepest descent point
return step * gradAtZero ;
}
2012-03-18 13:13:40 +08:00
2011-08-19 02:06:35 +08:00
}