| 
									
										
										
										
											2010-10-14 12:54:38 +08:00
										 |  |  | /* ----------------------------------------------------------------------------
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * GTSAM Copyright 2010, Georgia Tech Research Corporation,  | 
					
						
							|  |  |  |  * 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 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * -------------------------------------------------------------------------- */ | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											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>
 | 
					
						
							| 
									
										
										
										
											2012-06-03 00:18:40 +08:00
										 |  |  | #include <gtsam/nonlinear/Values.h>
 | 
					
						
							| 
									
										
										
										
											2010-08-20 01:23:19 +08:00
										 |  |  | #include <gtsam/nonlinear/NonlinearFactor.h>
 | 
					
						
							| 
									
										
										
										
											2011-12-10 00:36:50 +08:00
										 |  |  | #include <gtsam/nonlinear/NonlinearFactorGraph.h>
 | 
					
						
							| 
									
										
										
										
											2010-04-08 03:09:14 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | // \namespace
 | 
					
						
							| 
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 |  |  | namespace simulated2DOriented { | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   using namespace gtsam; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-02-06 06:34:35 +08:00
										 |  |  |   /// Specialized Values structure with syntactic sugar for
 | 
					
						
							|  |  |  |   /// compatibility with matlab
 | 
					
						
							|  |  |  |   class Values: public gtsam::Values { | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |     int nrPoses_, nrPoints_; | 
					
						
							| 
									
										
										
										
											2012-02-06 06:34:35 +08:00
										 |  |  |   public: | 
					
						
							|  |  |  |     Values() : nrPoses_(0), nrPoints_(0)  {} | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-06-03 00:18:40 +08:00
										 |  |  |     /// insert a pose
 | 
					
						
							|  |  |  |     void insertPose(Key i, const Pose2& p) { | 
					
						
							|  |  |  |       insert(i, p); | 
					
						
							| 
									
										
										
										
											2012-02-06 06:34:35 +08:00
										 |  |  |       nrPoses_++; | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-06-03 00:18:40 +08:00
										 |  |  |     /// insert a landmark
 | 
					
						
							|  |  |  |     void insertPoint(Key j, const Point2& p) { | 
					
						
							|  |  |  |       insert(j, p); | 
					
						
							| 
									
										
										
										
											2012-02-06 06:34:35 +08:00
										 |  |  |       nrPoints_++; | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |     int nrPoses() const {  return nrPoses_;  } ///< nr of poses
 | 
					
						
							|  |  |  |     int nrPoints() const { return nrPoints_;  } ///< nr of landmarks
 | 
					
						
							| 
									
										
										
										
											2012-02-06 06:34:35 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |     Pose2 pose(Key i) const { return at<Pose2>(i);  } ///< get a pose
 | 
					
						
							| 
									
										
										
										
											2012-06-03 00:18:40 +08:00
										 |  |  |     Point2 point(Key j) const { return at<Point2>(j); } ///< get a landmark
 | 
					
						
							| 
									
										
										
										
											2012-02-06 06:34:35 +08:00
										 |  |  |   }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 |  |  |   //TODO:: point prior is not implemented right now
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /// Prior on a single pose
 | 
					
						
							|  |  |  |   inline Pose2 prior(const Pose2& x) { | 
					
						
							|  |  |  |     return x; | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /// Prior on a single pose, optional derivative version
 | 
					
						
							| 
									
										
										
										
											2013-06-11 22:35:22 +08:00
										 |  |  |   Pose2 prior(const Pose2& x, boost::optional<Matrix&> H = boost::none) { | 
					
						
							|  |  |  |     if (H) *H = gtsam::eye(3); | 
					
						
							|  |  |  |     return x; | 
					
						
							|  |  |  |   } | 
					
						
							| 
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   /// odometry between two poses
 | 
					
						
							|  |  |  |   inline Pose2 odo(const Pose2& x1, const Pose2& x2) { | 
					
						
							|  |  |  |     return x1.between(x2); | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /// odometry between two poses, optional derivative version
 | 
					
						
							|  |  |  |   Pose2 odo(const Pose2& x1, const Pose2& x2, boost::optional<Matrix&> H1 = | 
					
						
							| 
									
										
										
										
											2013-06-11 22:35:22 +08:00
										 |  |  |       boost::none, boost::optional<Matrix&> H2 = boost::none) { | 
					
						
							|  |  |  |     return x1.between(x2, H1, H2); | 
					
						
							|  |  |  |   } | 
					
						
							| 
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   /// Unary factor encoding a soft prior on a vector
 | 
					
						
							| 
									
										
										
										
											2012-02-06 08:44:25 +08:00
										 |  |  |   template<class VALUE = Pose2> | 
					
						
							| 
									
										
										
										
											2012-02-21 05:52:47 +08:00
										 |  |  |   struct GenericPosePrior: public NoiseModelFactor1<VALUE> { | 
					
						
							| 
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-02-06 08:44:25 +08:00
										 |  |  |     Pose2 measured_; ///< measurement
 | 
					
						
							| 
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |     /// Create generic pose prior
 | 
					
						
							| 
									
										
										
										
											2012-02-19 09:02:07 +08:00
										 |  |  |     GenericPosePrior(const Pose2& measured, const SharedNoiseModel& model, Key key) : | 
					
						
							| 
									
										
										
										
											2012-02-21 05:52:47 +08:00
										 |  |  |       NoiseModelFactor1<VALUE>(model, key), measured_(measured) { | 
					
						
							| 
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 |  |  |     } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     /// Evaluate error and optionally derivative
 | 
					
						
							|  |  |  |     Vector evaluateError(const Pose2& x, boost::optional<Matrix&> H = | 
					
						
							|  |  |  |         boost::none) const { | 
					
						
							| 
									
										
										
										
											2012-02-06 08:44:25 +08:00
										 |  |  |       return measured_.localCoordinates(prior(x, H)); | 
					
						
							| 
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 |  |  |     } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   }; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /**
 | 
					
						
							|  |  |  |    * Binary factor simulating "odometry" between two Vectors | 
					
						
							|  |  |  |    */ | 
					
						
							| 
									
										
										
										
											2012-02-06 08:44:25 +08:00
										 |  |  |   template<class VALUE = Pose2> | 
					
						
							| 
									
										
										
										
											2012-02-21 05:52:47 +08:00
										 |  |  |   struct GenericOdometry: public NoiseModelFactor2<VALUE, VALUE> { | 
					
						
							| 
									
										
										
										
											2012-02-06 08:44:25 +08:00
										 |  |  |     Pose2 measured_;   ///< Between measurement for odometry factor
 | 
					
						
							| 
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-05-22 04:54:40 +08:00
										 |  |  |     typedef GenericOdometry<VALUE> This; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 |  |  |     /**
 | 
					
						
							|  |  |  |      * Creates an odometry factor between two poses | 
					
						
							|  |  |  |      */ | 
					
						
							| 
									
										
										
										
											2012-02-06 08:44:25 +08:00
										 |  |  |     GenericOdometry(const Pose2& measured, const SharedNoiseModel& model, | 
					
						
							| 
									
										
										
										
											2012-02-19 09:02:07 +08:00
										 |  |  |         Key i1, Key i2) : | 
					
						
							| 
									
										
										
										
											2012-02-21 05:52:47 +08:00
										 |  |  |           NoiseModelFactor2<VALUE, VALUE>(model, i1, i2), measured_(measured) { | 
					
						
							| 
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 |  |  |     } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-05-22 04:54:40 +08:00
										 |  |  |     virtual ~GenericOdometry() {} | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 |  |  |     /// Evaluate error and optionally derivative
 | 
					
						
							| 
									
										
										
										
											2012-02-07 07:32:59 +08:00
										 |  |  |     Vector evaluateError(const VALUE& x1, const VALUE& x2, | 
					
						
							| 
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 |  |  |         boost::optional<Matrix&> H1 = boost::none, | 
					
						
							|  |  |  |         boost::optional<Matrix&> H2 = boost::none) const { | 
					
						
							| 
									
										
										
										
											2012-02-06 08:44:25 +08:00
										 |  |  |       return measured_.localCoordinates(odo(x1, x2, H1, H2)); | 
					
						
							| 
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 |  |  |     } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |     /// @return a deep copy of this factor
 | 
					
						
							| 
									
										
										
										
											2012-06-10 05:06:06 +08:00
										 |  |  |     virtual gtsam::NonlinearFactor::shared_ptr clone() const { | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |       return boost::static_pointer_cast<gtsam::NonlinearFactor>( | 
					
						
							|  |  |  |           gtsam::NonlinearFactor::shared_ptr(new This(*this))); } | 
					
						
							| 
									
										
										
										
											2012-05-22 04:54:40 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 |  |  |   }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-02-06 08:44:25 +08:00
										 |  |  |   typedef GenericOdometry<Pose2> Odometry; | 
					
						
							| 
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   /// Graph specialization for syntactic sugar use with matlab
 | 
					
						
							| 
									
										
										
										
											2012-02-06 08:44:25 +08:00
										 |  |  |   class Graph : public NonlinearFactorGraph { | 
					
						
							| 
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 |  |  |   public: | 
					
						
							|  |  |  |     Graph() {} | 
					
						
							|  |  |  |     // TODO: add functions to add factors
 | 
					
						
							|  |  |  |   }; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | } // namespace simulated2DOriented
 |