2013-02-20 05:37:17 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/* ----------------------------------------------------------------------------
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2019-02-11 22:39:48 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								 * GTSAM Copyright 2010, Georgia Tech Research Corporation,
							 | 
						
					
						
							
								
									
										
										
										
											2013-02-20 05:37:17 +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
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 * -------------------------------------------------------------------------- */
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/**
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 * @file    ConcurrentBatchSmoother.cpp
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 * @brief   A Levenberg-Marquardt Batch Smoother that implements the
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 *          Concurrent Filtering and Smoothing interface.
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 * @author  Stephen Williams
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 */
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								#include <gtsam_unstable/nonlinear/ConcurrentBatchSmoother.h>
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-09 23:48:53 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								#include <gtsam/nonlinear/LinearContainerFactor.h>
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								#include <gtsam/linear/GaussianJunctionTree.h>
							 | 
						
					
						
							
								
									
										
										
										
											2013-02-20 05:37:17 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								#include <gtsam/base/timing.h>
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-09 23:48:53 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								#include <gtsam/base/debug.h>
							 | 
						
					
						
							
								
									
										
										
										
											2013-02-20 05:37:17 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								namespace gtsam {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/* ************************************************************************* */
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								void ConcurrentBatchSmoother::print(const std::string& s, const KeyFormatter& keyFormatter) const {
							 | 
						
					
						
							
								
									
										
										
										
											2013-02-20 05:37:17 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  std::cout << s;
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  std::cout << "  Factors:" << std::endl;
							 | 
						
					
						
							
								
									
										
										
										
											2016-05-21 23:52:14 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  for(const NonlinearFactor::shared_ptr& factor: factors_) {
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    PrintNonlinearFactor(factor, "    ", keyFormatter);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  }
							 | 
						
					
						
							
								
									
										
										
										
											2013-02-20 05:37:17 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  theta_.print("Values:\n");
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								}
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								/* ************************************************************************* */
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								bool ConcurrentBatchSmoother::equals(const ConcurrentSmoother& rhs, double tol) const {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  const ConcurrentBatchSmoother* smoother = dynamic_cast<const ConcurrentBatchSmoother*>(&rhs);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  return smoother
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      && factors_.equals(smoother->factors_)
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      && theta_.equals(smoother->theta_)
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      && ordering_.equals(smoother->ordering_)
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      && delta_.equals(smoother->delta_)
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      && separatorValues_.equals(smoother->separatorValues_);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								}
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2013-02-20 05:37:17 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/* ************************************************************************* */
							 | 
						
					
						
							
								
									
										
										
										
											2013-10-04 03:51:56 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								ConcurrentBatchSmoother::Result ConcurrentBatchSmoother::update(const NonlinearFactorGraph& newFactors, const Values& newTheta,
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    const boost::optional< std::vector<size_t> >& removeFactorIndices) {
							 | 
						
					
						
							
								
									
										
										
										
											2013-02-20 05:37:17 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  gttic(update);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  // Create the return result meta-data
							 | 
						
					
						
							
								
									
										
										
										
											2013-02-20 05:37:17 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  Result result;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  // Update all of the internal variables with the new information
							 | 
						
					
						
							
								
									
										
										
										
											2013-02-20 05:37:17 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  gttic(augment_system);
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-10 23:22:28 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    // Add the new variables to theta
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    theta_.insert(newTheta);
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-14 06:30:08 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-10 23:22:28 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    // Add new variables to the end of the ordering
							 | 
						
					
						
							
								
									
										
										
										
											2021-01-05 09:46:16 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    for(const auto key_value: newTheta) {
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-10 23:22:28 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								      ordering_.push_back(key_value.key);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    }
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-14 06:30:08 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-10 23:22:28 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    // Augment Delta
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-14 06:30:08 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    delta_.insert(newTheta.zeroVectors());
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-10 23:22:28 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    // Add the new factors to the graph, updating the variable index
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    insertFactors(newFactors);
							 | 
						
					
						
							
								
									
										
										
										
											2013-10-04 03:51:56 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    if(removeFactorIndices)
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      removeFactors(*removeFactorIndices);
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  }
							 | 
						
					
						
							
								
									
										
										
										
											2013-02-20 05:37:17 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  gttoc(augment_system);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  if(factors_.size() > 0) {
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-19 20:13:43 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    // Reorder the system to ensure efficient optimization (and marginalization) performance
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    gttic(reorder);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    reorder();
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    gttoc(reorder);
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-19 20:13:43 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    // Optimize the factors using a modified version of L-M
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    gttic(optimize);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    result = optimize();
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    gttoc(optimize);
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-10 23:22:28 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  }
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-09 23:48:53 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2013-05-10 02:59:22 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  // TODO: The following code does considerable work, much of which could be redundant given the previous optimization step
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // Refactor this code to reduce computational burden
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // Calculate the marginal on the separator from the smoother factors
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  if(separatorValues_.size() > 0) {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    gttic(presync);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    updateSmootherSummarization();
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    gttoc(presync);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  gttoc(update);
							 | 
						
					
						
							
								
									
										
										
										
											2013-02-20 05:37:17 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  return result;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								}
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/* ************************************************************************* */
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								void ConcurrentBatchSmoother::presync() {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  gttic(presync);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  gttoc(presync);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								}
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/* ************************************************************************* */
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-11 20:42:45 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								void ConcurrentBatchSmoother::getSummarizedFactors(NonlinearFactorGraph& summarizedFactors, Values& separatorValues) {
							 | 
						
					
						
							
								
									
										
										
										
											2013-02-20 05:37:17 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  gttic(get_summarized_factors);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // Copy the previous calculated smoother summarization factors into the output
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  summarizedFactors.push_back(smootherSummarization_);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-11 20:42:45 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  // Copy the separator values into the output
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  separatorValues.insert(separatorValues_);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-09 01:42:26 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  gttoc(get_summarized_factors);
							 | 
						
					
						
							
								
									
										
										
										
											2013-02-20 05:37:17 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								}
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/* ************************************************************************* */
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								void ConcurrentBatchSmoother::synchronize(const NonlinearFactorGraph& smootherFactors, const Values& smootherValues,
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-09 23:48:53 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    const NonlinearFactorGraph& summarizedFactors, const Values& separatorValues) {
							 | 
						
					
						
							
								
									
										
										
										
											2013-02-20 05:37:17 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  gttic(synchronize);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // Remove the previous filter summarization from the graph
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  removeFactors(filterSummarizationSlots_);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // Insert new linpoints into the values, augment the ordering, and store new dims to augment delta
							 | 
						
					
						
							
								
									
										
										
										
											2021-01-05 09:46:16 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  for(const auto key_value: smootherValues) {
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-14 06:30:08 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    std::pair<Values::iterator, bool> iter_inserted = theta_.tryInsert(key_value.key, key_value.value);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    if(iter_inserted.second) {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      // If the insert succeeded
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								      ordering_.push_back(key_value.key);
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-14 06:30:08 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								      delta_.insert(key_value.key, Vector::Zero(key_value.value.dim()));
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    } else {
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-14 06:30:08 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								      // If the element already existed in theta_
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      iter_inserted.first->value = key_value.value;
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  }
							 | 
						
					
						
							
								
									
										
										
										
											2021-01-05 09:46:16 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  for(const auto key_value: separatorValues) {
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-14 06:30:08 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    std::pair<Values::iterator, bool> iter_inserted = theta_.tryInsert(key_value.key, key_value.value);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    if(iter_inserted.second) {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      // If the insert succeeded
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								      ordering_.push_back(key_value.key);
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-14 06:30:08 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								      delta_.insert(key_value.key, Vector::Zero(key_value.value.dim()));
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    } else {
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-14 06:30:08 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								      // If the element already existed in theta_
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      iter_inserted.first->value = key_value.value;
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    }
							 | 
						
					
						
							
								
									
										
										
										
											2013-02-20 05:37:17 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // Insert the new smoother factors
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  insertFactors(smootherFactors);
							 | 
						
					
						
							
								
									
										
										
										
											2013-02-20 05:37:17 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  // Insert the new filter summarized factors
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  filterSummarizationSlots_ = insertFactors(summarizedFactors);
							 | 
						
					
						
							
								
									
										
										
										
											2013-02-20 05:37:17 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // Update the list of root keys
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-09 23:48:53 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  separatorValues_ = separatorValues;
							 | 
						
					
						
							
								
									
										
										
										
											2013-02-20 05:37:17 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  gttoc(synchronize);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								}
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/* ************************************************************************* */
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								void ConcurrentBatchSmoother::postsync() {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  gttic(postsync);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  gttoc(postsync);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								}
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/* ************************************************************************* */
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								std::vector<size_t> ConcurrentBatchSmoother::insertFactors(const NonlinearFactorGraph& factors) {
							 | 
						
					
						
							
								
									
										
										
										
											2013-02-20 05:37:17 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-09 01:42:26 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  gttic(insert_factors);
							 | 
						
					
						
							
								
									
										
										
										
											2013-02-20 05:37:17 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  // create the output vector
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  std::vector<size_t> slots;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  slots.reserve(factors.size());
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2013-02-20 05:37:17 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // Insert the factor into an existing hole in the factor graph, if possible
							 | 
						
					
						
							
								
									
										
										
										
											2016-05-21 23:52:14 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  for(const NonlinearFactor::shared_ptr& factor: factors) {
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    size_t slot;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    if(availableSlots_.size() > 0) {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      slot = availableSlots_.front();
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      availableSlots_.pop();
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      factors_.replace(slot, factor);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    } else {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      slot = factors_.size();
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      factors_.push_back(factor);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    slots.push_back(slot);
							 | 
						
					
						
							
								
									
										
										
										
											2013-02-20 05:37:17 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  gttoc(insert_factors);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  return slots;
							 | 
						
					
						
							
								
									
										
										
										
											2013-02-20 05:37:17 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								}
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/* ************************************************************************* */
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								void ConcurrentBatchSmoother::removeFactors(const std::vector<size_t>& slots) {
							 | 
						
					
						
							
								
									
										
										
										
											2013-02-20 05:37:17 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  gttic(remove_factors);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  // For each factor slot to delete...
							 | 
						
					
						
							
								
									
										
										
										
											2016-05-21 23:52:14 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  for(size_t slot: slots) {
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    // Remove the factor from the graph
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    factors_.remove(slot);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    // Mark the factor slot as available
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    availableSlots_.push(slot);
							 | 
						
					
						
							
								
									
										
										
										
											2013-02-20 05:37:17 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  }
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2013-02-20 05:37:17 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  gttoc(remove_factors);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								}
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/* ************************************************************************* */
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								void ConcurrentBatchSmoother::reorder() {
							 | 
						
					
						
							
								
									
										
										
										
											2013-02-20 05:37:17 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-10 23:22:28 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  // Recalculate the variable index
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-14 06:30:08 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  variableIndex_ = VariableIndex(factors_);
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-10 23:22:28 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2015-06-24 12:35:32 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  KeyVector separatorKeys = separatorValues_.keys();
							 | 
						
					
						
							
								
									
										
										
										
											2018-11-08 13:58:50 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  ordering_ = Ordering::ColamdConstrainedLast(variableIndex_, KeyVector(separatorKeys.begin(), separatorKeys.end()));
							 | 
						
					
						
							
								
									
										
										
										
											2013-02-20 05:37:17 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								}
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-09 23:48:53 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								/* ************************************************************************* */
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								ConcurrentBatchSmoother::Result ConcurrentBatchSmoother::optimize() {
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-09 23:48:53 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  // Create output result structure
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  Result result;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  result.nonlinearVariables = theta_.size() - separatorValues_.size();
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  result.linearVariables = separatorValues_.size();
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-09 23:48:53 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-11 01:15:20 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  // Pull out parameters we'll use
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  const LevenbergMarquardtParams::VerbosityLM lmVerbosity = parameters_.verbosityLM;
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  double lambda = parameters_.lambdaInitial;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // Create a Values that holds the current evaluation point
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-14 06:30:08 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  Values evalpoint = theta_.retract(delta_);
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  result.error = factors_.error(evalpoint);
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-11 01:15:20 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  if(result.error < parameters_.errorTol) {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    return result;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  }
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-09 23:48:53 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // Use a custom optimization loop so the linearization points can be controlled
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  double previousError;
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  VectorValues newDelta;
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-09 23:48:53 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  do {
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    previousError = result.error;
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-09 23:48:53 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    // Do next iteration
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    gttic(optimizer_iteration);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      // Linearize graph around the linearization point
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-14 06:30:08 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								      GaussianFactorGraph linearFactorGraph = *factors_.linearize(theta_);
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-09 23:48:53 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      // Keep increasing lambda until we make make progress
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      while(true) {
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-11 01:15:20 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								        if (lmVerbosity >= LevenbergMarquardtParams::TRYLAMBDA)
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								          std::cout << "trying lambda = " << lambda << std::endl;
							 | 
						
					
						
							
								
									
										
										
										
											2019-02-11 22:39:48 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-09 23:48:53 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								        // Add prior factors at the current solution
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								        gttic(damp);
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								        GaussianFactorGraph dampedFactorGraph(linearFactorGraph);
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-09 23:48:53 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								        dampedFactorGraph.reserve(linearFactorGraph.size() + delta_.size());
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								        {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								          // for each of the variables, add a prior at the current solution
							 | 
						
					
						
							
								
									
										
										
										
											2016-05-21 23:52:14 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								          for(const VectorValues::KeyValuePair& key_value: delta_) {
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-14 06:30:08 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								            size_t dim = key_value.second.size();
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								            Matrix A = Matrix::Identity(dim,dim);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								            Vector b = key_value.second;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								            SharedDiagonal model = noiseModel::Isotropic::Sigma(dim, 1.0 / std::sqrt(lambda));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								            GaussianFactor::shared_ptr prior(new JacobianFactor(key_value.first, A, b, model));
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-09 23:48:53 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								            dampedFactorGraph.push_back(prior);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								          }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								        }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								        gttoc(damp);
							 | 
						
					
						
							
								
									
										
										
										
											2019-02-11 22:39:48 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								        if (lmVerbosity >= LevenbergMarquardtParams::DAMPED)
							 | 
						
					
						
							
								
									
										
										
										
											2013-10-11 01:52:57 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								          dampedFactorGraph.print("damped");
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								        result.lambdas++;
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-14 06:30:08 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								        gttic(solve);
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-09 23:48:53 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								        // Solve Damped Gaussian Factor Graph
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-14 06:30:08 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								        newDelta = dampedFactorGraph.optimize(ordering_, parameters_.getEliminationFunction());
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-09 23:48:53 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								        // update the evalpoint with the new delta
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-14 06:30:08 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								        evalpoint = theta_.retract(newDelta);
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								        gttoc(solve);
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-09 23:48:53 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2019-02-11 22:39:48 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								        if (lmVerbosity >= LevenbergMarquardtParams::TRYLAMBDA)
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-11 01:15:20 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								          std::cout << "linear delta norm = " << newDelta.norm() << std::endl;
							 | 
						
					
						
							
								
									
										
										
										
											2019-02-11 22:39:48 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								        if (lmVerbosity >= LevenbergMarquardtParams::TRYDELTA)
							 | 
						
					
						
							
								
									
										
										
										
											2013-10-11 01:52:57 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								          newDelta.print("delta");
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-11 01:15:20 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-09 23:48:53 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								        // Evaluate the new error
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								        gttic(compute_error);
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								        double error = factors_.error(evalpoint);
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-09 23:48:53 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								        gttoc(compute_error);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2019-02-11 22:39:48 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								        if (lmVerbosity >= LevenbergMarquardtParams::TRYLAMBDA)
							 | 
						
					
						
							
								
									
										
										
										
											2013-10-11 01:52:57 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								          std::cout << "next error = " << error << std::endl;
							 | 
						
					
						
							
								
									
										
										
										
											2019-02-11 22:39:48 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								        if(error < result.error) {
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-09 23:48:53 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								          // Keep this change
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								          // Update the error value
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								          result.error = error;
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-09 23:48:53 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								          // Update the linearization point
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								          theta_ = evalpoint;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								          // Reset the deltas to zeros
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								          delta_.setZero();
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								          // Put the linearization points and deltas back for specific variables
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-09 23:48:53 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								          if(separatorValues_.size() > 0) {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								            theta_.update(separatorValues_);
							 | 
						
					
						
							
								
									
										
										
										
											2021-01-05 09:46:16 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								            for(const auto key_value: separatorValues_) {
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-14 06:30:08 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								              delta_.at(key_value.key) = newDelta.at(key_value.key);
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-09 23:48:53 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								            }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								          }
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-14 06:30:08 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-09 23:48:53 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								          // Decrease lambda for next time
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-11 01:15:20 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								          lambda /= parameters_.lambdaFactor;
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-09 23:48:53 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								          // End this lambda search iteration
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								          break;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								        } else {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								          // Reject this change
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-11 01:15:20 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								          if(lambda >= parameters_.lambdaUpperBound) {
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-09 23:48:53 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								            // The maximum lambda has been used. Print a warning and end the search.
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								            std::cout << "Warning:  Levenberg-Marquardt giving up because cannot decrease error with maximum lambda" << std::endl;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								            break;
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-11 01:15:20 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								          } else {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								            // Increase lambda and continue searching
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								            lambda *= parameters_.lambdaFactor;
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-11 01:16:19 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								          }
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-09 23:48:53 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								        }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      } // end while
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    gttoc(optimizer_iteration);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-11 01:15:20 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    if (lmVerbosity >= LevenbergMarquardtParams::LAMBDA)
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      std::cout << "using lambda = " << lambda << std::endl;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    result.iterations++;
							 | 
						
					
						
							
								
									
										
										
										
											2014-05-06 23:54:45 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  } while(result.iterations < (size_t)parameters_.maxIterations &&
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-11 01:15:20 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								      !checkConvergence(parameters_.relativeErrorTol, parameters_.absoluteErrorTol, parameters_.errorTol, previousError, result.error, NonlinearOptimizerParams::SILENT));
							 | 
						
					
						
							
								
									
										
										
										
											2013-02-20 05:37:17 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  return result;
							 | 
						
					
						
							
								
									
										
										
										
											2013-02-20 05:37:17 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								}
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-10 23:22:28 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								/* ************************************************************************* */
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								void ConcurrentBatchSmoother::updateSmootherSummarization() {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // The smoother summarization factors are the resulting marginal factors on the separator
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // variables that result from marginalizing out all of the other variables
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // These marginal factors will be cached for later transmission to the filter using
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // linear container factors
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-11 01:15:20 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  // Create a nonlinear factor graph without the filter summarization factors
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  NonlinearFactorGraph graph(factors_);
							 | 
						
					
						
							
								
									
										
										
										
											2016-05-21 23:52:14 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  for(size_t slot: filterSummarizationSlots_) {
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-11 01:15:20 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    graph.remove(slot);
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-10 23:22:28 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-11 01:15:20 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  // Get the set of separator keys
							 | 
						
					
						
							
								
									
										
										
										
											2015-06-21 09:38:25 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  gtsam::KeySet separatorKeys;
							 | 
						
					
						
							
								
									
										
										
										
											2021-01-05 09:46:16 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  for(const auto key_value: separatorValues_) {
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-11 01:15:20 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    separatorKeys.insert(key_value.key);
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-10 23:22:28 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-11 01:15:20 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  // Calculate the marginal factors on the separator
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  smootherSummarization_ = internal::calculateMarginalFactors(graph, theta_, separatorKeys, parameters_.getEliminationFunction());
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-10 23:22:28 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								}
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-09 23:48:53 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								/* ************************************************************************* */
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								void ConcurrentBatchSmoother::PrintNonlinearFactor(const NonlinearFactor::shared_ptr& factor, const std::string& indent, const KeyFormatter& keyFormatter) {
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-09 23:48:53 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  std::cout << indent;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  if(factor) {
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    if(boost::dynamic_pointer_cast<LinearContainerFactor>(factor)) {
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-09 23:48:53 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								      std::cout << "l( ";
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    } else {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      std::cout << "f( ";
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    }
							 | 
						
					
						
							
								
									
										
										
										
											2016-05-21 23:52:14 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    for(Key key: *factor) {
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-09 23:48:53 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								      std::cout << keyFormatter(key) << " ";
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    std::cout << ")" << std::endl;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  } else {
							 | 
						
					
						
							
								
									
										
										
										
											2020-04-07 05:31:05 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    std::cout << "{ nullptr }" << std::endl;
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-09 23:48:53 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								}
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/* ************************************************************************* */
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-14 06:30:08 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								void ConcurrentBatchSmoother::PrintLinearFactor(const GaussianFactor::shared_ptr& factor, const std::string& indent, const KeyFormatter& keyFormatter) {
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-09 23:48:53 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  std::cout << indent;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  if(factor) {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    std::cout << "g( ";
							 | 
						
					
						
							
								
									
										
										
										
											2016-05-21 23:52:14 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    for(Key key: *factor) {
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-14 06:30:08 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								      std::cout << keyFormatter(key) << " ";
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-09 23:48:53 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    std::cout << ")" << std::endl;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  } else {
							 | 
						
					
						
							
								
									
										
										
										
											2020-04-07 05:31:05 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    std::cout << "{ nullptr }" << std::endl;
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-09 23:48:53 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								}
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2013-04-10 23:22:28 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								/* ************************************************************************* */
							 | 
						
					
						
							
								
									
										
										
										
											2013-02-20 05:37:17 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								}/// namespace gtsam
							 |