| 
									
										
										
										
											2013-02-28 04:23:47 +08:00
										 |  |  | /* ----------------------------------------------------------------------------
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2016-06-19 14:13:59 +08:00
										 |  |  |  * GTSAM Copyright 2010, Georgia Tech Research Corporation, | 
					
						
							| 
									
										
										
										
											2013-02-28 04:23:47 +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    FixedLagSmoother.h | 
					
						
							|  |  |  |  * @brief   Base class for a fixed-lag smoother. This mimics the basic interface to iSAM2. | 
					
						
							|  |  |  |  * | 
					
						
							|  |  |  |  * @author  Stephen Williams | 
					
						
							|  |  |  |  * @date    Feb 27, 2013 | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // \callgraph
 | 
					
						
							|  |  |  | #pragma once
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-03-14 02:56:21 +08:00
										 |  |  | #include <gtsam_unstable/base/dllexport.h>
 | 
					
						
							| 
									
										
										
										
											2013-06-06 23:36:11 +08:00
										 |  |  | #include <gtsam/inference/Key.h>
 | 
					
						
							| 
									
										
										
										
											2013-02-28 04:23:47 +08:00
										 |  |  | #include <gtsam/nonlinear/NonlinearFactorGraph.h>
 | 
					
						
							|  |  |  | #include <gtsam/nonlinear/Values.h>
 | 
					
						
							| 
									
										
										
										
											2016-06-19 14:13:59 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-02-28 04:23:47 +08:00
										 |  |  | #include <map>
 | 
					
						
							| 
									
										
										
										
											2016-06-19 14:13:59 +08:00
										 |  |  | #include <vector>
 | 
					
						
							| 
									
										
										
										
											2013-02-28 04:23:47 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | namespace gtsam { | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-03-14 02:56:21 +08:00
										 |  |  | class GTSAM_UNSTABLE_EXPORT FixedLagSmoother { | 
					
						
							| 
									
										
										
										
											2013-02-28 04:23:47 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | public: | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /// Typedef for a shared pointer to an Incremental Fixed-Lag Smoother
 | 
					
						
							|  |  |  |   typedef boost::shared_ptr<FixedLagSmoother> shared_ptr; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /// Typedef for a Key-Timestamp map/database
 | 
					
						
							|  |  |  |   typedef std::map<Key, double> KeyTimestampMap; | 
					
						
							|  |  |  |   typedef std::multimap<double, Key> TimestampKeyMap; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /**
 | 
					
						
							|  |  |  |    * Meta information returned about the update | 
					
						
							|  |  |  |    */ | 
					
						
							|  |  |  |   // TODO: Think of some more things to put here
 | 
					
						
							|  |  |  |   struct Result { | 
					
						
							|  |  |  |     size_t iterations; ///< The number of optimizer iterations performed
 | 
					
						
							| 
									
										
										
										
											2013-04-26 02:10:21 +08:00
										 |  |  |     size_t intermediateSteps; ///< The number of intermediate steps performed within the optimization. For L-M, this is the number of lambdas tried.
 | 
					
						
							| 
									
										
										
										
											2013-02-28 04:23:47 +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-26 02:10:21 +08:00
										 |  |  |     Result() : iterations(0), intermediateSteps(0), nonlinearVariables(0), linearVariables(0), error(0) {}; | 
					
						
							| 
									
										
										
										
											2013-04-16 01:53:33 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |     /// Getter methods
 | 
					
						
							|  |  |  |     size_t getIterations() const { return iterations; } | 
					
						
							| 
									
										
										
										
											2013-04-26 02:10:21 +08:00
										 |  |  |     size_t getIntermediateSteps() const { return intermediateSteps; } | 
					
						
							| 
									
										
										
										
											2013-04-16 01:53:33 +08:00
										 |  |  |     size_t getNonlinearVariables() const { return nonlinearVariables; } | 
					
						
							|  |  |  |     size_t getLinearVariables() const { return linearVariables; } | 
					
						
							|  |  |  |     double getError() const { return error; } | 
					
						
							| 
									
										
										
										
											2013-02-28 04:23:47 +08:00
										 |  |  |   }; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /** default constructor */ | 
					
						
							| 
									
										
										
										
											2013-08-19 23:32:08 +08:00
										 |  |  |   FixedLagSmoother(double smootherLag = 0.0) : smootherLag_(smootherLag) { } | 
					
						
							| 
									
										
										
										
											2013-02-28 04:23:47 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   /** destructor */ | 
					
						
							| 
									
										
										
										
											2013-08-19 23:32:08 +08:00
										 |  |  |   virtual ~FixedLagSmoother() { } | 
					
						
							| 
									
										
										
										
											2013-02-28 04:23:47 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   /** Print the factor for debugging and testing (implementing Testable) */ | 
					
						
							|  |  |  |   virtual void print(const std::string& s = "FixedLagSmoother:\n", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /** Check if two IncrementalFixedLagSmoother Objects are equal */ | 
					
						
							|  |  |  |   virtual bool equals(const FixedLagSmoother& rhs, double tol = 1e-9) const; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-04-16 01:53:33 +08:00
										 |  |  |   /** read the current smoother lag */ | 
					
						
							|  |  |  |   double smootherLag() const { | 
					
						
							|  |  |  |     return smootherLag_; | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /** write to the current smoother lag */ | 
					
						
							|  |  |  |   double& smootherLag() { | 
					
						
							|  |  |  |     return smootherLag_; | 
					
						
							|  |  |  |   } | 
					
						
							| 
									
										
										
										
											2013-02-28 04:23:47 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   /** Access the current set of timestamps associated with each variable */ | 
					
						
							| 
									
										
										
										
											2013-04-16 01:53:33 +08:00
										 |  |  |   const KeyTimestampMap& timestamps() const { | 
					
						
							| 
									
										
										
										
											2013-02-28 04:23:47 +08:00
										 |  |  |     return keyTimestampMap_; | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-04-16 01:53:33 +08:00
										 |  |  |   /** Add new factors, updating the solution and relinearizing as needed. */ | 
					
						
							|  |  |  |   virtual Result update(const NonlinearFactorGraph& newFactors = NonlinearFactorGraph(), const Values& newTheta = Values(), | 
					
						
							|  |  |  |       const KeyTimestampMap& timestamps = KeyTimestampMap()) = 0; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-02-28 04:23:47 +08:00
										 |  |  |   /** Compute an estimate from the incomplete linear delta computed during the last update.
 | 
					
						
							|  |  |  |    * This delta is incomplete because it was not updated below wildfire_threshold.  If only | 
					
						
							|  |  |  |    * a single variable is needed, it is faster to call calculateEstimate(const KEY&). | 
					
						
							|  |  |  |    */ | 
					
						
							|  |  |  |   virtual Values calculateEstimate() const  = 0; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | protected: | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /** The length of the smoother lag. Any variable older than this amount will be marginalized out. */ | 
					
						
							|  |  |  |   double smootherLag_; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /** The current timestamp associated with each tracked key */ | 
					
						
							|  |  |  |   TimestampKeyMap timestampKeyMap_; | 
					
						
							|  |  |  |   KeyTimestampMap keyTimestampMap_; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /** Update the Timestamps associated with the keys */ | 
					
						
							|  |  |  |   void updateKeyTimestampMap(const KeyTimestampMap& newTimestamps); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /** Erase keys from the Key-Timestamps database */ | 
					
						
							| 
									
										
										
										
											2016-06-19 14:13:59 +08:00
										 |  |  |   void eraseKeyTimestampMap(const KeyVector& keys); | 
					
						
							| 
									
										
										
										
											2013-02-28 04:23:47 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   /** Find the most recent timestamp of the system */ | 
					
						
							|  |  |  |   double getCurrentTimestamp() const; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /** Find all of the keys associated with timestamps before the provided time */ | 
					
						
							| 
									
										
										
										
											2016-06-19 14:13:59 +08:00
										 |  |  |   KeyVector findKeysBefore(double timestamp) const; | 
					
						
							| 
									
										
										
										
											2013-02-28 04:23:47 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   /** Find all of the keys associated with timestamps before the provided time */ | 
					
						
							| 
									
										
										
										
											2016-06-19 14:13:59 +08:00
										 |  |  |   KeyVector findKeysAfter(double timestamp) const; | 
					
						
							| 
									
										
										
										
											2013-02-28 04:23:47 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | }; // FixedLagSmoother
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-04-16 01:53:33 +08:00
										 |  |  | /// Typedef for matlab wrapping
 | 
					
						
							|  |  |  | typedef FixedLagSmoother::KeyTimestampMap FixedLagSmootherKeyTimestampMap; | 
					
						
							| 
									
										
										
										
											2013-04-16 03:54:46 +08:00
										 |  |  | typedef FixedLagSmootherKeyTimestampMap::value_type FixedLagSmootherKeyTimestampMapValue; | 
					
						
							| 
									
										
										
										
											2013-04-16 01:53:33 +08:00
										 |  |  | typedef FixedLagSmoother::Result FixedLagSmootherResult; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-02-28 04:23:47 +08:00
										 |  |  | } /// namespace gtsam
 |