| 
									
										
										
										
											2009-12-10 01:29:43 +08:00
										 |  |  | /**
 | 
					
						
							| 
									
										
										
										
											2009-12-10 07:43:01 +08:00
										 |  |  |  *  @file  Pose2Factor.H | 
					
						
							| 
									
										
										
										
											2009-12-10 01:29:43 +08:00
										 |  |  |  *  @authors Frank Dellaert, Viorela Ila | 
					
						
							|  |  |  |  **/ | 
					
						
							| 
									
										
										
										
											2009-12-11 07:45:38 +08:00
										 |  |  | #pragma once
 | 
					
						
							| 
									
										
										
										
											2009-12-10 01:29:43 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | #include <map>
 | 
					
						
							| 
									
										
										
										
											2009-12-11 07:45:38 +08:00
										 |  |  | #include "NonlinearFactor.h"
 | 
					
						
							| 
									
										
										
										
											2009-12-10 01:29:43 +08:00
										 |  |  | #include "GaussianFactor.h"
 | 
					
						
							|  |  |  | #include "VectorConfig.h"
 | 
					
						
							|  |  |  | #include "Pose2.h"
 | 
					
						
							|  |  |  | #include "Matrix.h"
 | 
					
						
							| 
									
										
										
										
											2009-12-10 03:55:25 +08:00
										 |  |  | #include "Pose2Config.h"
 | 
					
						
							| 
									
										
										
										
											2009-12-10 07:43:01 +08:00
										 |  |  | #include "ostream"
 | 
					
						
							| 
									
										
										
										
											2009-12-10 01:29:43 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | namespace gtsam { | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-12-11 07:45:38 +08:00
										 |  |  | class Pose2Factor : public NonlinearFactor<Pose2Config> { | 
					
						
							| 
									
										
										
										
											2009-12-10 01:29:43 +08:00
										 |  |  | private: | 
					
						
							|  |  |  | 	std::string key1_, key2_; /** The keys of the two poses, order matters */ | 
					
						
							|  |  |  | 	Pose2 measured_; | 
					
						
							|  |  |  | 	Matrix square_root_inverse_covariance_; /** sqrt(inv(measurement_covariance)) */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | public: | 
					
						
							| 
									
										
										
										
											2009-12-11 07:45:38 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	typedef boost::shared_ptr<Pose2Factor> shared_ptr; // shorthand for a smart pointer to a factor
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-12-10 07:43:01 +08:00
										 |  |  | 	Pose2Factor(const std::string& key1, const std::string& key2, | 
					
						
							| 
									
										
										
										
											2009-12-10 01:29:43 +08:00
										 |  |  | 			const Pose2& measured, const Matrix& measurement_covariance): key1_(key1),key2_(key2),measured_(measured) { | 
					
						
							|  |  |  | 		square_root_inverse_covariance_ = inverse_square_root(measurement_covariance); | 
					
						
							|  |  |  | 	} | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	/** implement functions needed for Testable */ | 
					
						
							| 
									
										
										
										
											2009-12-10 07:43:01 +08:00
										 |  |  | 	void print(const std::string& name) const { | 
					
						
							|  |  |  | 		std::cout << name << std::endl; | 
					
						
							| 
									
										
										
										
											2009-12-11 07:45:38 +08:00
										 |  |  | 		std::cout << "Factor "<< std::endl; | 
					
						
							| 
									
										
										
										
											2009-12-10 07:43:01 +08:00
										 |  |  | 		std::cout << "key1 "<< key1_<<std::endl; | 
					
						
							|  |  |  | 		std::cout << "key2 "<< key2_<<std::endl; | 
					
						
							|  |  |  | 		measured_.print("measured "); | 
					
						
							|  |  |  | 		gtsam::print(square_root_inverse_covariance_,"MeasurementCovariance"); | 
					
						
							|  |  |  | 	} | 
					
						
							| 
									
										
										
										
											2009-12-11 07:45:38 +08:00
										 |  |  | 	bool equals(const NonlinearFactor<Pose2Config>& expected, double tol) const {return false;} | 
					
						
							| 
									
										
										
										
											2009-12-10 01:29:43 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	/** implement functions needed to derive from Factor */ | 
					
						
							| 
									
										
										
										
											2009-12-11 07:45:38 +08:00
										 |  |  | 	Vector error_vector(const Pose2Config& config) const { | 
					
						
							|  |  |  | 		//z-h
 | 
					
						
							|  |  |  | 		Pose2 p1 = config.get(key1_), p2 = config.get(key2_); | 
					
						
							|  |  |  | 		return (measured_ - between(p1,p2)).vector(); | 
					
						
							|  |  |  | 	} | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-12-10 01:29:43 +08:00
										 |  |  | 	std::list<std::string> keys() const { std::list<std::string> l; return l; } | 
					
						
							|  |  |  | 	std::size_t size() const { return 2;} | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	/** linearize */ | 
					
						
							|  |  |  | 	boost::shared_ptr<GaussianFactor> linearize(const Pose2Config& config) const { | 
					
						
							|  |  |  | 		Pose2 p1 = config.get(key1_), p2 = config.get(key2_); | 
					
						
							|  |  |  | 		Vector b = (measured_ - between(p1,p2)).vector(); | 
					
						
							|  |  |  | 		Matrix H1 = Dbetween1(p1,p2); | 
					
						
							|  |  |  | 		Matrix H2 = Dbetween2(p1,p2); | 
					
						
							|  |  |  | 		boost::shared_ptr<GaussianFactor> linearized(new GaussianFactor( | 
					
						
							|  |  |  | 				key1_, square_root_inverse_covariance_ * H1, | 
					
						
							|  |  |  | 				key2_, square_root_inverse_covariance_ * H2, | 
					
						
							|  |  |  | 				b, 1.0)); | 
					
						
							|  |  |  | 		return linearized; | 
					
						
							|  |  |  | 	} | 
					
						
							|  |  |  | }; | 
					
						
							|  |  |  | } /// namespace gtsam
 |