| 
									
										
										
										
											2013-02-20 05:37:17 +08:00
										 |  |  | /* ----------------------------------------------------------------------------
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * GTSAM Copyright 2010, Georgia Tech Research Corporation,  | 
					
						
							|  |  |  |  * Atlanta, Georgia 30332-0415 | 
					
						
							|  |  |  |  * All Rights Reserved | 
					
						
							|  |  |  |  * Authors: Frank Dellaert, et al. (see THANKS for the full author list) | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * See LICENSE for the license information | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * -------------------------------------------------------------------------- */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /**
 | 
					
						
							|  |  |  |  * @file    ConcurrentBatchSmoother.h | 
					
						
							|  |  |  |  * @brief   A Levenberg-Marquardt Batch Smoother that implements the | 
					
						
							|  |  |  |  *          Concurrent Filtering and Smoothing interface. | 
					
						
							|  |  |  |  * @author  Stephen Williams | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // \callgraph
 | 
					
						
							|  |  |  | #pragma once
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-04-09 23:48:53 +08:00
										 |  |  | #include <gtsam_unstable/nonlinear/ConcurrentFilteringAndSmoothing.h>
 | 
					
						
							| 
									
										
										
										
											2013-02-20 05:37:17 +08:00
										 |  |  | #include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
 | 
					
						
							|  |  |  | #include <queue>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | namespace gtsam { | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /**
 | 
					
						
							|  |  |  |  * A Levenberg-Marquardt Batch Smoother that implements the Concurrent Filtering and Smoother interface. | 
					
						
							|  |  |  |  */ | 
					
						
							| 
									
										
										
										
											2013-03-14 02:56:21 +08:00
										 |  |  | class GTSAM_UNSTABLE_EXPORT ConcurrentBatchSmoother : public ConcurrentSmoother { | 
					
						
							| 
									
										
										
										
											2013-02-20 05:37:17 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | public: | 
					
						
							| 
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 |  |  |   typedef boost::shared_ptr<ConcurrentBatchSmoother> shared_ptr; | 
					
						
							| 
									
										
										
										
											2013-02-20 05:37:17 +08:00
										 |  |  |   typedef ConcurrentSmoother Base; ///< typedef for base class
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 |  |  |   /** Meta information returned about the update */ | 
					
						
							| 
									
										
										
										
											2013-02-20 05:37:17 +08:00
										 |  |  |   struct Result { | 
					
						
							|  |  |  |     size_t iterations; ///< The number of optimizer iterations performed
 | 
					
						
							| 
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 |  |  |     size_t lambdas; ///< The number of different L-M lambda factors that were tried during optimization
 | 
					
						
							| 
									
										
										
										
											2013-02-20 05:37:17 +08:00
										 |  |  |     size_t nonlinearVariables; ///< The number of variables that can be relinearized
 | 
					
						
							|  |  |  |     size_t linearVariables; ///< The number of variables that must keep a constant linearization point
 | 
					
						
							|  |  |  |     double error; ///< The final factor graph error
 | 
					
						
							| 
									
										
										
										
											2013-04-16 03:54:46 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |     /// Constructor
 | 
					
						
							| 
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 |  |  |     Result() : iterations(0), lambdas(0), nonlinearVariables(0), linearVariables(0), error(0) {}; | 
					
						
							| 
									
										
										
										
											2013-04-16 03:54:46 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |     /// Getter methods
 | 
					
						
							|  |  |  |     size_t getIterations() const { return iterations; } | 
					
						
							|  |  |  |     size_t getLambdas() const { return lambdas; } | 
					
						
							|  |  |  |     size_t getNonlinearVariables() const { return nonlinearVariables; } | 
					
						
							|  |  |  |     size_t getLinearVariables() const { return linearVariables; } | 
					
						
							|  |  |  |     double getError() const { return error; } | 
					
						
							| 
									
										
										
										
											2013-02-20 05:37:17 +08:00
										 |  |  |   }; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /** Default constructor */ | 
					
						
							| 
									
										
										
										
											2013-04-12 20:52:29 +08:00
										 |  |  |   ConcurrentBatchSmoother(const LevenbergMarquardtParams& parameters = LevenbergMarquardtParams()) : parameters_(parameters) {}; | 
					
						
							| 
									
										
										
										
											2013-02-20 05:37:17 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   /** Default destructor */ | 
					
						
							|  |  |  |   virtual ~ConcurrentBatchSmoother() {}; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 |  |  |   /** Implement a GTSAM standard 'print' function */ | 
					
						
							| 
									
										
										
										
											2013-08-11 01:15:20 +08:00
										 |  |  |   virtual void print(const std::string& s = "Concurrent Batch Smoother:\n", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const; | 
					
						
							| 
									
										
										
										
											2013-02-20 05:37:17 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 |  |  |   /** Check if two Concurrent Smoothers are equal */ | 
					
						
							| 
									
										
										
										
											2013-08-11 01:15:20 +08:00
										 |  |  |   virtual bool equals(const ConcurrentSmoother& rhs, double tol = 1e-9) const; | 
					
						
							| 
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   /** Access the current set of factors */ | 
					
						
							|  |  |  |   const NonlinearFactorGraph& getFactors() const { | 
					
						
							|  |  |  |     return factors_; | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /** Access the current linearization point */ | 
					
						
							|  |  |  |   const Values& getLinearizationPoint() const { | 
					
						
							|  |  |  |     return theta_; | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /** Access the current ordering */ | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   const Ordering& getOrdering() const { | 
					
						
							| 
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 |  |  |     return ordering_; | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /** Access the current set of deltas to the linearization point */ | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:44 +08:00
										 |  |  |   const VectorValues& getDelta() const { | 
					
						
							| 
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 |  |  |     return delta_; | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-02-20 05:37:17 +08:00
										 |  |  |   /** Compute the current best estimate of all variables and return a full Values structure.
 | 
					
						
							|  |  |  |    * If only a single variable is needed, it may be faster to call calculateEstimate(const KEY&). | 
					
						
							|  |  |  |    */ | 
					
						
							|  |  |  |   Values calculateEstimate() const { | 
					
						
							| 
									
										
										
										
											2013-08-09 04:08:54 +08:00
										 |  |  |     return theta_.retract(delta_); | 
					
						
							| 
									
										
										
										
											2013-02-20 05:37:17 +08:00
										 |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /** Compute the current best estimate of a single variable. This is generally faster than
 | 
					
						
							|  |  |  |    * calling the no-argument version of calculateEstimate if only specific variables are needed. | 
					
						
							|  |  |  |    * @param key | 
					
						
							|  |  |  |    * @return | 
					
						
							|  |  |  |    */ | 
					
						
							|  |  |  |   template<class VALUE> | 
					
						
							| 
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 |  |  |   VALUE calculateEstimate(Key key) const { | 
					
						
							| 
									
										
										
										
											2013-08-14 06:30:08 +08:00
										 |  |  |     const Vector delta = delta_.at(key); | 
					
						
							| 
									
										
										
										
											2013-04-10 23:22:28 +08:00
										 |  |  |     return theta_.at<VALUE>(key).retract(delta); | 
					
						
							| 
									
										
										
										
											2013-02-20 05:37:17 +08:00
										 |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /**
 | 
					
						
							|  |  |  |    * Add new factors and variables to the smoother. | 
					
						
							|  |  |  |    * | 
					
						
							|  |  |  |    * Add new measurements, and optionally new variables, to the smoother. | 
					
						
							|  |  |  |    * This runs a full step of the ISAM2 algorithm, relinearizing and updating | 
					
						
							|  |  |  |    * the solution as needed, according to the wildfire and relinearize | 
					
						
							|  |  |  |    * thresholds. | 
					
						
							|  |  |  |    * | 
					
						
							|  |  |  |    * @param newFactors The new factors to be added to the smoother | 
					
						
							|  |  |  |    * @param newTheta Initialization points for new variables to be added to the smoother | 
					
						
							|  |  |  |    * You must include here all new variables occuring in newFactors (which were not already | 
					
						
							|  |  |  |    * in the smoother).  There must not be any variables here that do not occur in newFactors, | 
					
						
							|  |  |  |    * and additionally, variables that were already in the system must not be included here. | 
					
						
							|  |  |  |    */ | 
					
						
							| 
									
										
										
										
											2013-10-04 03:51:56 +08:00
										 |  |  |   virtual Result update(const NonlinearFactorGraph& newFactors = NonlinearFactorGraph(), const Values& newTheta = Values(), | 
					
						
							|  |  |  |       const boost::optional< std::vector<size_t> >& removeFactorIndices = boost::none); | 
					
						
							| 
									
										
										
										
											2013-02-20 05:37:17 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   /**
 | 
					
						
							|  |  |  |    * Perform any required operations before the synchronization process starts. | 
					
						
							|  |  |  |    * Called by 'synchronize' | 
					
						
							|  |  |  |    */ | 
					
						
							|  |  |  |   virtual void presync(); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /**
 | 
					
						
							|  |  |  |    * Populate the provided containers with factors that constitute the smoother branch summarization | 
					
						
							|  |  |  |    * needed by the filter. | 
					
						
							|  |  |  |    * | 
					
						
							|  |  |  |    * @param summarizedFactors The summarized factors for the filter branch | 
					
						
							|  |  |  |    */ | 
					
						
							| 
									
										
										
										
											2013-04-11 20:42:45 +08:00
										 |  |  |   virtual void getSummarizedFactors(NonlinearFactorGraph& summarizedFactors, Values& separatorValues); | 
					
						
							| 
									
										
										
										
											2013-02-20 05:37:17 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   /**
 | 
					
						
							|  |  |  |    * Apply the new smoother factors sent by the filter, and the updated version of the filter | 
					
						
							|  |  |  |    * branch summarized factors. | 
					
						
							|  |  |  |    * | 
					
						
							|  |  |  |    * @param smootherFactors A set of new factors added to the smoother from the filter | 
					
						
							|  |  |  |    * @param smootherValues Linearization points for any new variables | 
					
						
							|  |  |  |    * @param summarizedFactors An updated version of the filter branch summarized factors | 
					
						
							|  |  |  |    * @param rootValues The linearization point of the root variables | 
					
						
							|  |  |  |    */ | 
					
						
							|  |  |  |   virtual void synchronize(const NonlinearFactorGraph& smootherFactors, const Values& smootherValues, | 
					
						
							| 
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 |  |  |       const NonlinearFactorGraph& summarizedFactors, const Values& separatorValues); | 
					
						
							| 
									
										
										
										
											2013-02-20 05:37:17 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   /**
 | 
					
						
							|  |  |  |    * Perform any required operations after the synchronization process finishes. | 
					
						
							|  |  |  |    * Called by 'synchronize' | 
					
						
							|  |  |  |    */ | 
					
						
							|  |  |  |   virtual void postsync(); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-08-11 01:15:20 +08:00
										 |  |  | protected: | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   LevenbergMarquardtParams parameters_;  ///< LM parameters
 | 
					
						
							|  |  |  |   NonlinearFactorGraph factors_;  ///< The set of all factors currently in the smoother
 | 
					
						
							|  |  |  |   Values theta_;  ///< Current linearization point of all variables in the smoother
 | 
					
						
							|  |  |  |   Ordering ordering_; ///< The current ordering used to calculate the linear deltas
 | 
					
						
							|  |  |  |   VectorValues delta_; ///< The current set of linear deltas from the linearization point
 | 
					
						
							|  |  |  |   VariableIndex variableIndex_; ///< The current variable index, which allows efficient factor lookup by variable
 | 
					
						
							|  |  |  |   std::queue<size_t> availableSlots_; ///< The set of available factor graph slots caused by deleting factors
 | 
					
						
							|  |  |  |   Values separatorValues_; ///< The linearization points of the separator variables. These should not be updated during optimization.
 | 
					
						
							|  |  |  |   std::vector<size_t> filterSummarizationSlots_;  ///< The slots in factor graph that correspond to the current filter summarization factors
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Storage for information to be sent to the filter
 | 
					
						
							|  |  |  |   NonlinearFactorGraph smootherSummarization_; ///< A temporary holding place for calculated smoother summarization
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-04-10 23:22:28 +08:00
										 |  |  | private: | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 |  |  |   /** Augment the graph with new factors
 | 
					
						
							| 
									
										
										
										
											2013-02-20 05:37:17 +08:00
										 |  |  |    * | 
					
						
							| 
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 |  |  |    * @param factors The factors to add to the graph | 
					
						
							|  |  |  |    * @return The slots in the graph where they were inserted | 
					
						
							| 
									
										
										
										
											2013-02-20 05:37:17 +08:00
										 |  |  |    */ | 
					
						
							| 
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 |  |  |   std::vector<size_t> insertFactors(const NonlinearFactorGraph& factors); | 
					
						
							| 
									
										
										
										
											2013-02-20 05:37:17 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 |  |  |   /** Remove factors from the graph by slot index
 | 
					
						
							|  |  |  |    * | 
					
						
							|  |  |  |    * @param slots The slots in the factor graph that should be deleted | 
					
						
							|  |  |  |    * */ | 
					
						
							|  |  |  |   void removeFactors(const std::vector<size_t>& slots); | 
					
						
							| 
									
										
										
										
											2013-02-20 05:37:17 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 |  |  |   /** Use colamd to update into an efficient ordering */ | 
					
						
							|  |  |  |   void reorder(); | 
					
						
							| 
									
										
										
										
											2013-02-20 05:37:17 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 |  |  |   /** Use a modified version of L-M to update the linearization point and delta */ | 
					
						
							|  |  |  |   Result optimize(); | 
					
						
							| 
									
										
										
										
											2013-02-20 05:37:17 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-04-10 23:22:28 +08:00
										 |  |  |   /** Calculate the smoother marginal factors on the separator variables */ | 
					
						
							|  |  |  |   void updateSmootherSummarization(); | 
					
						
							| 
									
										
										
										
											2013-04-09 23:48:53 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-04-10 23:22:28 +08:00
										 |  |  |   /** Print just the nonlinear keys in a nonlinear factor */ | 
					
						
							| 
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 |  |  |   static void PrintNonlinearFactor(const NonlinearFactor::shared_ptr& factor, | 
					
						
							|  |  |  |       const std::string& indent = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter); | 
					
						
							| 
									
										
										
										
											2013-04-09 23:48:53 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-04-10 23:22:28 +08:00
										 |  |  |   /** Print just the nonlinear keys in a linear factor */ | 
					
						
							| 
									
										
										
										
											2013-08-14 06:30:08 +08:00
										 |  |  |   static void PrintLinearFactor(const GaussianFactor::shared_ptr& factor, | 
					
						
							| 
									
										
										
										
											2013-04-10 05:24:05 +08:00
										 |  |  |       const std::string& indent = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter); | 
					
						
							| 
									
										
										
										
											2013-02-20 05:37:17 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | }; // ConcurrentBatchSmoother
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-04-16 03:54:46 +08:00
										 |  |  | /// Typedef for Matlab wrapping
 | 
					
						
							|  |  |  | typedef ConcurrentBatchSmoother::Result ConcurrentBatchSmootherResult; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-12-22 05:02:06 +08:00
										 |  |  | /// traits
 | 
					
						
							|  |  |  | template<> | 
					
						
							| 
									
										
										
										
											2014-12-26 23:47:51 +08:00
										 |  |  | struct traits<ConcurrentBatchSmoother> : public Testable<ConcurrentBatchSmoother> { | 
					
						
							| 
									
										
										
										
											2014-12-22 05:02:06 +08:00
										 |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | } //\ namespace gtsam
 |