| 
									
										
										
										
											2009-12-25 07:44:08 +08:00
										 |  |  | /**
 | 
					
						
							| 
									
										
										
										
											2010-01-17 02:01:16 +08:00
										 |  |  |  *  @file  PriorFactor.h | 
					
						
							|  |  |  |  *  @authors Frank Dellaert | 
					
						
							| 
									
										
										
										
											2009-12-25 07:44:08 +08:00
										 |  |  |  **/ | 
					
						
							|  |  |  | #pragma once
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-17 02:01:16 +08:00
										 |  |  | #include <ostream>
 | 
					
						
							| 
									
										
										
										
											2010-01-17 11:56:42 +08:00
										 |  |  | #include "NoiseModel.h"
 | 
					
						
							| 
									
										
										
										
											2009-12-25 07:44:08 +08:00
										 |  |  | #include "NonlinearFactor.h"
 | 
					
						
							|  |  |  | #include "Pose2.h"
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | namespace gtsam { | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-17 00:46:57 +08:00
										 |  |  | 	/**
 | 
					
						
							|  |  |  | 	 * A class for a soft prior on any Lie type | 
					
						
							|  |  |  | 	 * T is the Lie group type, Config where the T's are gotten from | 
					
						
							|  |  |  | 	 */ | 
					
						
							|  |  |  | 	template<class Config, class Key, class T> | 
					
						
							|  |  |  | 	class PriorFactor: public NonlinearFactor1<Config, Key, T> { | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	private: | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 		typedef NonlinearFactor1<Config, Key, T> Base; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 		T prior_; /** The measurement */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	public: | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 		// shorthand for a smart pointer to a factor
 | 
					
						
							|  |  |  | 		typedef typename boost::shared_ptr<PriorFactor> shared_ptr; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 		/** Constructor */ | 
					
						
							| 
									
										
										
										
											2010-01-17 11:56:42 +08:00
										 |  |  | 		PriorFactor(const Key& key, const T& prior, | 
					
						
							| 
									
										
										
										
											2010-01-23 01:36:57 +08:00
										 |  |  | 				const SharedGaussian& model) : | 
					
						
							| 
									
										
										
										
											2010-01-18 13:38:53 +08:00
										 |  |  | 			Base(model, key), prior_(prior) { | 
					
						
							| 
									
										
										
										
											2010-01-17 00:46:57 +08:00
										 |  |  | 		} | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 		/** implement functions needed for Testable */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 		/** print */ | 
					
						
							|  |  |  | 		void print(const std::string& s) const { | 
					
						
							|  |  |  | 			Base::print(s); | 
					
						
							|  |  |  | 			prior_.print("prior"); | 
					
						
							|  |  |  | 		} | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 		/** equals */ | 
					
						
							|  |  |  | 		bool equals(const NonlinearFactor<Config>& expected, double tol) const { | 
					
						
							|  |  |  | 			const PriorFactor<Config, Key, T> *e = dynamic_cast<const PriorFactor< | 
					
						
							|  |  |  | 					Config, Key, T>*> (&expected); | 
					
						
							|  |  |  | 			return e != NULL && Base::equals(expected) && this->prior_.equals( | 
					
						
							|  |  |  | 					e->prior_, tol); | 
					
						
							|  |  |  | 		} | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 		/** implement functions needed to derive from Factor */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 		/** vector of errors */ | 
					
						
							|  |  |  | 		Vector evaluateError(const T& p, boost::optional<Matrix&> H = boost::none) const { | 
					
						
							| 
									
										
										
										
											2010-01-18 13:38:53 +08:00
										 |  |  | 			if (H) (*H) = eye(dim(p)); | 
					
						
							| 
									
										
										
										
											2010-01-17 00:46:57 +08:00
										 |  |  | 			// manifold equivalent of h(x)-z -> log(z,h(x))
 | 
					
						
							| 
									
										
										
										
											2010-01-18 13:38:53 +08:00
										 |  |  | 			return logmap(prior_, p); | 
					
						
							| 
									
										
										
										
											2010-01-17 00:46:57 +08:00
										 |  |  | 		} | 
					
						
							|  |  |  | 	}; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-12-25 07:44:08 +08:00
										 |  |  | } /// namespace gtsam
 |