| 
									
										
										
										
											2013-06-24 16:24:56 +08:00
										 |  |  | /**
 | 
					
						
							|  |  |  |  * @file SmartRangeFactor.h | 
					
						
							|  |  |  |  * | 
					
						
							|  |  |  |  * @brief A smart factor for range-only SLAM that does initialization and marginalization | 
					
						
							|  |  |  |  *  | 
					
						
							|  |  |  |  * @date Sep 10, 2012 | 
					
						
							|  |  |  |  * @author Alex Cunningham | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #pragma once
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <gtsam_unstable/base/dllexport.h>
 | 
					
						
							|  |  |  | #include <gtsam/nonlinear/NonlinearFactor.h>
 | 
					
						
							| 
									
										
										
										
											2013-07-30 07:55:40 +08:00
										 |  |  | #include <gtsam/inference/Key.h>
 | 
					
						
							| 
									
										
										
										
											2013-06-24 16:24:56 +08:00
										 |  |  | #include <gtsam/geometry/Pose2.h>
 | 
					
						
							| 
									
										
										
										
											2013-08-09 04:08:54 +08:00
										 |  |  | #include <gtsam/base/timing.h>
 | 
					
						
							| 
									
										
										
										
											2013-06-24 16:24:56 +08:00
										 |  |  | #include <boost/foreach.hpp>
 | 
					
						
							|  |  |  | #include <map>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | namespace gtsam { | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /**
 | 
					
						
							|  |  |  |  * Smart factor for range SLAM | 
					
						
							|  |  |  |  * @addtogroup SLAM | 
					
						
							|  |  |  |  */ | 
					
						
							| 
									
										
										
										
											2013-06-25 03:30:00 +08:00
										 |  |  | class SmartRangeFactor: public NoiseModelFactor { | 
					
						
							| 
									
										
										
										
											2013-06-24 16:24:56 +08:00
										 |  |  | protected: | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   struct Circle2 { | 
					
						
							|  |  |  |     Circle2(const Point2& p, double r) : | 
					
						
							|  |  |  |         center(p), radius(r) { | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  |     Point2 center; | 
					
						
							|  |  |  |     double radius; | 
					
						
							|  |  |  |   }; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-24 23:31:13 +08:00
										 |  |  |   typedef SmartRangeFactor This; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   std::vector<double> measurements_; ///< Range measurements
 | 
					
						
							| 
									
										
										
										
											2013-06-24 23:57:03 +08:00
										 |  |  |   double variance_; ///< variance on noise
 | 
					
						
							| 
									
										
										
										
											2013-06-24 16:24:56 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | public: | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /** Default constructor: don't use directly */ | 
					
						
							|  |  |  |   SmartRangeFactor() { | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-24 23:57:03 +08:00
										 |  |  |   /**
 | 
					
						
							|  |  |  |    * Constructor | 
					
						
							|  |  |  |    * @param s standard deviation of range measurement noise | 
					
						
							|  |  |  |    */ | 
					
						
							|  |  |  |   SmartRangeFactor(double s) : | 
					
						
							|  |  |  |       NoiseModelFactor(noiseModel::Isotropic::Sigma(1, s)), variance_(s * s) { | 
					
						
							| 
									
										
										
										
											2013-06-24 16:24:56 +08:00
										 |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   virtual ~SmartRangeFactor() { | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /// Add a range measurement to a pose with given key.
 | 
					
						
							|  |  |  |   void addRange(Key key, double measuredRange) { | 
					
						
							| 
									
										
										
										
											2013-06-24 20:07:21 +08:00
										 |  |  |     keys_.push_back(key); | 
					
						
							| 
									
										
										
										
											2013-06-24 20:15:01 +08:00
										 |  |  |     measurements_.push_back(measuredRange); | 
					
						
							| 
									
										
										
										
											2013-06-24 23:57:03 +08:00
										 |  |  |     size_t n = keys_.size(); | 
					
						
							|  |  |  |     // Since we add the errors, the noise variance adds
 | 
					
						
							|  |  |  |     noiseModel_ = noiseModel::Isotropic::Variance(1, n * variance_); | 
					
						
							| 
									
										
										
										
											2013-06-24 16:24:56 +08:00
										 |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-24 20:15:01 +08:00
										 |  |  |   // Testable
 | 
					
						
							| 
									
										
										
										
											2013-06-24 16:24:56 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   /** print */ | 
					
						
							|  |  |  |   virtual void print(const std::string& s = "", | 
					
						
							|  |  |  |       const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { | 
					
						
							| 
									
										
										
										
											2013-06-26 01:13:02 +08:00
										 |  |  |     std::cout << s << "SmartRangeFactor with " << size() << " measurements\n"; | 
					
						
							|  |  |  |     NoiseModelFactor::print(s); | 
					
						
							| 
									
										
										
										
											2013-06-24 16:24:56 +08:00
										 |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /** Check if two factors are equal */ | 
					
						
							|  |  |  |   virtual bool equals(const NonlinearFactor& f, double tol = 1e-9) const { | 
					
						
							|  |  |  |     return false; | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // factor interface
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /**
 | 
					
						
							|  |  |  |    * Triangulate a point from at least three pose-range pairs | 
					
						
							|  |  |  |    * Checks for best pair that includes first point | 
					
						
							|  |  |  |    */ | 
					
						
							| 
									
										
										
										
											2013-06-26 01:22:45 +08:00
										 |  |  |   Point2 triangulate(const Values& x) const { | 
					
						
							| 
									
										
										
										
											2013-09-14 08:21:10 +08:00
										 |  |  |     //gttic_(triangulate);
 | 
					
						
							| 
									
										
										
										
											2013-06-26 01:13:02 +08:00
										 |  |  |     // create n circles corresponding to measured range around each pose
 | 
					
						
							|  |  |  |     std::list<Circle2> circles; | 
					
						
							|  |  |  |     size_t n = size(); | 
					
						
							|  |  |  |     for (size_t j = 0; j < n; j++) { | 
					
						
							|  |  |  |       const Pose2& pose = x.at<Pose2>(keys_[j]); | 
					
						
							|  |  |  |       circles.push_back(Circle2(pose.translation(), measurements_[j])); | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-24 16:24:56 +08:00
										 |  |  |     Circle2 circle1 = circles.front(); | 
					
						
							|  |  |  |     boost::optional<Point2> best_fh; | 
					
						
							|  |  |  |     boost::optional<Circle2> best_circle; | 
					
						
							| 
									
										
										
										
											2013-06-25 00:18:48 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |     // loop over all circles
 | 
					
						
							| 
									
										
										
										
											2013-06-24 16:24:56 +08:00
										 |  |  |     BOOST_FOREACH(const Circle2& it, circles) { | 
					
						
							|  |  |  |       // distance between circle centers.
 | 
					
						
							|  |  |  |       double d = circle1.center.dist(it.center); | 
					
						
							| 
									
										
										
										
											2013-06-24 20:15:01 +08:00
										 |  |  |       if (d < 1e-9) | 
					
						
							| 
									
										
										
										
											2013-06-25 00:18:48 +08:00
										 |  |  |         continue; // skip circles that are in the same location
 | 
					
						
							|  |  |  |       // Find f and h, the intersection points in normalized circles
 | 
					
						
							| 
									
										
										
										
											2013-06-24 20:15:01 +08:00
										 |  |  |       boost::optional<Point2> fh = Point2::CircleCircleIntersection( | 
					
						
							|  |  |  |           circle1.radius / d, it.radius / d); | 
					
						
							| 
									
										
										
										
											2013-06-25 00:18:48 +08:00
										 |  |  |       // Check if this pair is better by checking h = fh->y()
 | 
					
						
							|  |  |  |       // if h is large, the intersections are well defined.
 | 
					
						
							| 
									
										
										
										
											2013-06-24 20:15:01 +08:00
										 |  |  |       if (fh && (!best_fh || fh->y() > best_fh->y())) { | 
					
						
							| 
									
										
										
										
											2013-06-24 16:24:56 +08:00
										 |  |  |         best_fh = fh; | 
					
						
							|  |  |  |         best_circle = it; | 
					
						
							|  |  |  |       } | 
					
						
							|  |  |  |     } | 
					
						
							| 
									
										
										
										
											2013-06-25 00:18:48 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |     // use best fh to find actual intersection points
 | 
					
						
							| 
									
										
										
										
											2013-06-25 00:25:02 +08:00
										 |  |  |     std::list<Point2> intersections = Point2::CircleCircleIntersection( | 
					
						
							| 
									
										
										
										
											2013-06-24 16:24:56 +08:00
										 |  |  |         circle1.center, best_circle->center, best_fh); | 
					
						
							| 
									
										
										
										
											2013-06-25 00:18:48 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-25 00:25:02 +08:00
										 |  |  |     // pick winner based on other measurements
 | 
					
						
							|  |  |  |     double error1 = 0, error2 = 0; | 
					
						
							|  |  |  |     Point2 p1 = intersections.front(), p2 = intersections.back(); | 
					
						
							|  |  |  |     BOOST_FOREACH(const Circle2& it, circles) { | 
					
						
							|  |  |  |       error1 += it.center.dist(p1); | 
					
						
							|  |  |  |       error2 += it.center.dist(p2); | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  |     return (error1 < error2) ? p1 : p2; | 
					
						
							| 
									
										
										
										
											2013-09-14 08:21:10 +08:00
										 |  |  |     //gttoc_(triangulate);
 | 
					
						
							| 
									
										
										
										
											2013-06-24 16:24:56 +08:00
										 |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /**
 | 
					
						
							|  |  |  |    * Error function *without* the NoiseModel, \f$ z-h(x) \f$. | 
					
						
							|  |  |  |    */ | 
					
						
							|  |  |  |   virtual Vector unwhitenedError(const Values& x, | 
					
						
							|  |  |  |       boost::optional<std::vector<Matrix>&> H = boost::none) const { | 
					
						
							| 
									
										
										
										
											2013-06-24 23:31:13 +08:00
										 |  |  |     size_t n = size(); | 
					
						
							| 
									
										
										
										
											2013-06-25 00:18:48 +08:00
										 |  |  |     if (n < 3) { | 
					
						
							|  |  |  |       if (H) | 
					
						
							|  |  |  |         // set Jacobians to zero for n<3
 | 
					
						
							|  |  |  |         for (size_t j = 0; j < n; j++) | 
					
						
							|  |  |  |           (*H)[j] = zeros(3, 1); | 
					
						
							|  |  |  |       return zero(1); | 
					
						
							|  |  |  |     } else { | 
					
						
							|  |  |  |       Vector error = zero(1); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-24 23:31:13 +08:00
										 |  |  |       // triangulate to get the optimized point
 | 
					
						
							| 
									
										
										
										
											2013-06-24 23:57:03 +08:00
										 |  |  |       // TODO: Should we have a (better?) variant that does this in relative coordinates ?
 | 
					
						
							| 
									
										
										
										
											2013-06-26 01:13:02 +08:00
										 |  |  |       Point2 optimizedPoint = triangulate(x); | 
					
						
							| 
									
										
										
										
											2013-06-25 00:18:48 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |       // TODO: triangulation should be followed by an optimization given poses
 | 
					
						
							| 
									
										
										
										
											2013-06-24 23:31:13 +08:00
										 |  |  |       // now evaluate the errors between predicted and measured range
 | 
					
						
							|  |  |  |       for (size_t j = 0; j < n; j++) { | 
					
						
							|  |  |  |         const Pose2& pose = x.at<Pose2>(keys_[j]); | 
					
						
							| 
									
										
										
										
											2013-06-24 23:57:03 +08:00
										 |  |  |         if (H) | 
					
						
							|  |  |  |           // also calculate 1*3 derivative for each of the n poses
 | 
					
						
							| 
									
										
										
										
											2013-06-25 00:18:48 +08:00
										 |  |  |           error[0] += pose.range(optimizedPoint, (*H)[j]) - measurements_[j]; | 
					
						
							| 
									
										
										
										
											2013-06-24 23:31:13 +08:00
										 |  |  |         else | 
					
						
							| 
									
										
										
										
											2013-06-25 00:18:48 +08:00
										 |  |  |           error[0] += pose.range(optimizedPoint) - measurements_[j]; | 
					
						
							| 
									
										
										
										
											2013-06-24 16:24:56 +08:00
										 |  |  |       } | 
					
						
							| 
									
										
										
										
											2013-06-25 00:18:48 +08:00
										 |  |  |       return error; | 
					
						
							| 
									
										
										
										
											2013-06-24 16:24:56 +08:00
										 |  |  |     } | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-24 23:31:13 +08:00
										 |  |  |   /// @return a deep copy of this factor
 | 
					
						
							|  |  |  |   virtual gtsam::NonlinearFactor::shared_ptr clone() const { | 
					
						
							|  |  |  |     return boost::static_pointer_cast<gtsam::NonlinearFactor>( | 
					
						
							| 
									
										
										
										
											2013-06-24 23:57:03 +08:00
										 |  |  |         gtsam::NonlinearFactor::shared_ptr(new This(*this))); | 
					
						
							|  |  |  |   } | 
					
						
							| 
									
										
										
										
											2013-06-24 23:31:13 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-24 16:24:56 +08:00
										 |  |  | }; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | } // \namespace gtsam
 | 
					
						
							|  |  |  | 
 |