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-08-20 01:23:19 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								#include <gtsam/linear/NoiseModel.h>
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								#include <gtsam/nonlinear/NonlinearFactor.h>
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								#include <gtsam/geometry/Pose2.h>
							 | 
						
					
						
							
								
									
										
										
										
											2009-12-25 07:44:08 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								namespace gtsam {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2010-01-17 00:46:57 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
									/**
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
									 * A class for a soft prior on any Lie type
							 | 
						
					
						
							
								
									
										
										
										
											2010-07-02 04:50:37 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
									 * It takes three template parameters:
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
									 *   T is the Lie group type for which the prior is define
							 | 
						
					
						
							
								
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
									 *   Key (typically TypedSymbol) is used to look up T's in a Values
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
									 *   Values where the T's are stored, typically LieValues<Key,T> or a TupleValues<...>
							 | 
						
					
						
							
								
									
										
										
										
											2010-07-02 04:50:37 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
									 * The Key type is not arbitrary: we need to cast to a Symbol at linearize, so
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
									 * a simple type like int will not work
							 | 
						
					
						
							
								
									
										
										
										
											2010-01-17 00:46:57 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
									 */
							 | 
						
					
						
							
								
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
									template<class Values, class Key>
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
									class PriorFactor: public NonlinearFactor1<Values, Key> {
							 | 
						
					
						
							
								
									
										
										
										
											2010-08-24 03:44:17 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
									public:
							 | 
						
					
						
							
								
									
										
										
										
											2010-10-09 11:53:27 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
										typedef typename Key::Value T;
							 | 
						
					
						
							
								
									
										
										
										
											2010-01-17 00:46:57 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
									private:
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
										typedef NonlinearFactor1<Values, Key> Base;
							 | 
						
					
						
							
								
									
										
										
										
											2010-01-17 00:46:57 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
										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 */
							 | 
						
					
						
							
								
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
										bool equals(const NonlinearFactor<Values>& expected, double tol) const {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
											const PriorFactor<Values, Key> *e = dynamic_cast<const PriorFactor<
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
													Values, Key>*> (&expected);
							 | 
						
					
						
							
								
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
											return e != NULL && Base::equals(expected, tol) && this->prior_.equals(
							 | 
						
					
						
							
								
									
										
										
										
											2010-01-17 00:46:57 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
													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-08-27 03:55:40 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
											if (H) (*H) = eye(p.dim());
							 | 
						
					
						
							
								
									
										
										
										
											2010-01-17 00:46:57 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
											// manifold equivalent of h(x)-z -> log(z,h(x))
							 | 
						
					
						
							
								
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
											return prior_.logmap(p);
							 | 
						
					
						
							
								
									
										
										
										
											2010-01-17 00:46:57 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
										}
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
									};
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2009-12-25 07:44:08 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								} /// namespace gtsam
							 |