| 
									
										
										
										
											2010-04-08 03:09:14 +08:00
										 |  |  | /**
 | 
					
						
							|  |  |  |  * @file    simulated2D.h | 
					
						
							|  |  |  |  * @brief   measurement functions and derivatives for simulated 2D robot | 
					
						
							|  |  |  |  * @author  Frank Dellaert | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // \callgraph
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #pragma once
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-20 01:23:19 +08:00
										 |  |  | #include <gtsam/geometry/Pose2.h>
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:55 +08:00
										 |  |  | #include <gtsam/nonlinear/TupleValues.h>
 | 
					
						
							| 
									
										
										
										
											2010-08-20 01:23:19 +08:00
										 |  |  | #include <gtsam/nonlinear/NonlinearFactor.h>
 | 
					
						
							| 
									
										
										
										
											2010-04-08 03:09:14 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | // \namespace
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | namespace gtsam { | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	namespace simulated2DOriented { | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 		// The types that take an oriented pose2 rather than point2
 | 
					
						
							|  |  |  | 		typedef TypedSymbol<Point2, 'l'> PointKey; | 
					
						
							|  |  |  | 		typedef TypedSymbol<Pose2,  'x'> PoseKey; | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:55 +08:00
										 |  |  | 		typedef LieValues<PoseKey> PoseConfig; | 
					
						
							|  |  |  | 		typedef LieValues<PointKey> PointConfig; | 
					
						
							|  |  |  | 		typedef TupleValues2<PoseConfig, PointConfig> Config; | 
					
						
							| 
									
										
										
										
											2010-04-08 03:09:14 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 		//TODO:: point prior is not implemented right now
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 		/**
 | 
					
						
							|  |  |  | 		 * Prior on a single pose, and optional derivative version | 
					
						
							|  |  |  | 		 */ | 
					
						
							|  |  |  | 		inline Pose2 prior(const Pose2& x) { | 
					
						
							|  |  |  | 			return x; | 
					
						
							|  |  |  | 		} | 
					
						
							|  |  |  | 		Pose2 prior(const Pose2& x, boost::optional<Matrix&> H = boost::none); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-04-08 05:27:16 +08:00
										 |  |  | 		/**
 | 
					
						
							|  |  |  | 		 * odometry between two poses, and optional derivative version | 
					
						
							|  |  |  | 		 */ | 
					
						
							|  |  |  | 		inline Pose2 odo(const Pose2& x1, const Pose2& x2) { | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  | 			return x1.between(x2); | 
					
						
							| 
									
										
										
										
											2010-04-08 05:27:16 +08:00
										 |  |  | 		} | 
					
						
							|  |  |  | 		Pose2 odo(const Pose2& x1, const Pose2& x2, boost::optional<Matrix&> H1 = | 
					
						
							|  |  |  | 				boost::none, boost::optional<Matrix&> H2 = boost::none); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-04-08 03:09:14 +08:00
										 |  |  | 		/**
 | 
					
						
							|  |  |  | 		 * Unary factor encoding a soft prior on a vector | 
					
						
							|  |  |  | 		 */ | 
					
						
							|  |  |  | 		template<class Cfg = Config, class Key = PoseKey> | 
					
						
							| 
									
										
										
										
											2010-08-24 03:44:17 +08:00
										 |  |  | 		struct GenericPosePrior: public NonlinearFactor1<Cfg, Key> { | 
					
						
							| 
									
										
										
										
											2010-04-08 03:09:14 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 			Pose2 z_; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 			GenericPosePrior(const Pose2& z, const SharedGaussian& model, const Key& key) : | 
					
						
							| 
									
										
										
										
											2010-08-24 03:44:17 +08:00
										 |  |  | 				NonlinearFactor1<Cfg, Key> (model, key), z_(z) { | 
					
						
							| 
									
										
										
										
											2010-04-08 03:09:14 +08:00
										 |  |  | 			} | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 			Vector evaluateError(const Pose2& x, boost::optional<Matrix&> H = | 
					
						
							|  |  |  | 					boost::none) const { | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  | 				return z_.logmap(prior(x, H)); | 
					
						
							| 
									
										
										
										
											2010-04-08 03:09:14 +08:00
										 |  |  | 			} | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 		}; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-04-08 05:27:16 +08:00
										 |  |  | 		/**
 | 
					
						
							|  |  |  | 		 * Binary factor simulating "odometry" between two Vectors | 
					
						
							|  |  |  | 		 */ | 
					
						
							|  |  |  | 		template<class Cfg = Config, class Key = PoseKey> | 
					
						
							| 
									
										
										
										
											2010-08-24 03:44:17 +08:00
										 |  |  | 		struct GenericOdometry: public NonlinearFactor2<Cfg, Key, Key> { | 
					
						
							| 
									
										
										
										
											2010-04-08 05:27:16 +08:00
										 |  |  | 			Pose2 z_; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 			GenericOdometry(const Pose2& z, const SharedGaussian& model, | 
					
						
							|  |  |  | 					const Key& i1, const Key& i2) : | 
					
						
							| 
									
										
										
										
											2010-08-24 03:44:17 +08:00
										 |  |  | 				NonlinearFactor2<Cfg, Key, Key> (model, i1, i2), z_(z) { | 
					
						
							| 
									
										
										
										
											2010-04-08 05:27:16 +08:00
										 |  |  | 			} | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 			Vector evaluateError(const Pose2& x1, const Pose2& x2, boost::optional< | 
					
						
							|  |  |  | 					Matrix&> H1 = boost::none, boost::optional<Matrix&> H2 = boost::none) const { | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  | 				return z_.logmap(odo(x1, x2, H1, H2)); | 
					
						
							| 
									
										
										
										
											2010-04-08 05:27:16 +08:00
										 |  |  | 			} | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 		}; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 		typedef GenericOdometry<Config, PoseKey> Odometry; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-04-08 03:09:14 +08:00
										 |  |  | 	} // namespace simulated2DOriented
 | 
					
						
							|  |  |  | } // namespace gtsam
 |