2010-10-14 12:54:38 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/* ----------------------------------------------------------------------------
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2019-02-11 22:39:48 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								 * GTSAM Copyright 2010, Georgia Tech Research Corporation,
							 | 
						
					
						
							
								
									
										
										
										
											2010-10-14 12:54:38 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 * 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
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 * -------------------------------------------------------------------------- */
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2009-08-22 06:23:24 +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/nonlinear/NonlinearFactor.h>
							 | 
						
					
						
							
								
									
										
										
										
											2011-12-10 00:36:50 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								#include <gtsam/nonlinear/NonlinearFactorGraph.h>
							 | 
						
					
						
							
								
									
										
										
										
											2014-12-22 05:02:06 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								#include <gtsam/geometry/Point2.h>
							 | 
						
					
						
							
								
									
										
										
										
											2023-01-07 08:29:15 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								#include "gtsam/base/OptionalJacobian.h"
							 | 
						
					
						
							
								
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								// \namespace
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								namespace simulated2D {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  using namespace gtsam;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // Simulated2D robots have no orientation, just a position
							 | 
						
					
						
							
								
									
										
										
										
											2012-02-06 08:44:25 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2012-02-06 06:34:35 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  /**
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								   *  Custom Values class that holds poses and points, mainly used as a convenience for MATLAB wrapper
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								   */
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  class Values: public gtsam::Values {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  private:
							 | 
						
					
						
							
								
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    int nrPoses_, nrPoints_;
							 | 
						
					
						
							
								
									
										
										
										
											2012-02-06 06:34:35 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  public:
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    typedef gtsam::Values Base;  ///< base class
							 | 
						
					
						
							
								
									
										
										
										
											2023-01-18 06:05:12 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    typedef std::shared_ptr<Point2> sharedPoint;  ///< shortcut to shared Point type
							 | 
						
					
						
							
								
									
										
										
										
											2012-02-06 06:34:35 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    /// Constructor
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    Values() : nrPoses_(0), nrPoints_(0) {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    /// Copy constructor
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    Values(const Base& base) :
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								        Base(base), nrPoses_(0), nrPoints_(0) {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    /// Insert a pose
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-03 00:18:40 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    void insertPose(Key i, const Point2& p) {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      insert(i, p);
							 | 
						
					
						
							
								
									
										
										
										
											2012-02-06 06:34:35 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      nrPoses_++;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    /// Insert a point
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-03 00:18:40 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    void insertPoint(Key j, const Point2& p) {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      insert(j, p);
							 | 
						
					
						
							
								
									
										
										
										
											2012-02-06 06:34:35 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      nrPoints_++;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    /// Number of poses
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    int nrPoses() const {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      return nrPoses_;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    /// Number of points
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    int nrPoints() const {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      return nrPoints_;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    /// Return pose i
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-03 00:18:40 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    Point2 pose(Key i) const {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      return at<Point2>(i);
							 | 
						
					
						
							
								
									
										
										
										
											2012-02-06 06:34:35 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    /// Return point j
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-03 00:18:40 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    Point2 point(Key j) const {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      return at<Point2>(j);
							 | 
						
					
						
							
								
									
										
										
										
											2012-02-06 06:34:35 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  };
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2014-02-24 07:53:48 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  /// Prior on a single pose
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  inline Point2 prior(const Point2& x) {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    return x;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  }
							 | 
						
					
						
							
								
									
										
										
										
											2012-02-06 06:34:35 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2014-02-24 07:53:48 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  /// Prior on a single pose, optionally returns derivative
							 | 
						
					
						
							
								
									
										
										
										
											2023-01-07 08:29:15 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  inline Point2 prior(const Point2& x, OptionalJacobian<2,2> H = OptionalNone) {
							 | 
						
					
						
							
								
									
										
										
										
											2016-04-12 03:11:29 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    if (H) *H = I_2x2;
							 | 
						
					
						
							
								
									
										
										
										
											2014-02-24 07:53:48 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    return x;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  }
							 | 
						
					
						
							
								
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2014-02-24 07:53:48 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  /// odometry between two poses
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  inline Point2 odo(const Point2& x1, const Point2& x2) {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    return x2 - x1;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  /// odometry between two poses, optionally returns derivative
							 | 
						
					
						
							
								
									
										
										
										
											2023-01-07 08:29:15 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  inline Point2 odo(const Point2& x1, const Point2& x2, 
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
										  OptionalJacobian<2,2> H1 = OptionalNone, 
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
										  OptionalJacobian<2,2> H2 = OptionalNone) {
							 | 
						
					
						
							
								
									
										
										
										
											2016-04-12 03:11:29 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								      if (H1) *H1 = -I_2x2;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      if (H2) *H2 = I_2x2;
							 | 
						
					
						
							
								
									
										
										
										
											2013-06-21 00:05:24 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								      return x2 - x1;
							 | 
						
					
						
							
								
									
										
										
										
											2014-02-24 07:53:48 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  }
							 | 
						
					
						
							
								
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2014-02-24 07:53:48 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  /// measurement between landmark and pose
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  inline Point2 mea(const Point2& x, const Point2& l) {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    return l - x;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  }
							 | 
						
					
						
							
								
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2014-02-24 07:53:48 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  /// measurement between landmark and pose, optionally returns derivative
							 | 
						
					
						
							
								
									
										
										
										
											2023-01-07 08:29:15 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  inline Point2 mea(const Point2& x, const Point2& l, OptionalJacobian<2,2> H1 =
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    OptionalNone, OptionalMatrixType H2 = OptionalNone) {
							 | 
						
					
						
							
								
									
										
										
										
											2016-04-12 03:11:29 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								      if (H1) *H1 = -I_2x2;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      if (H2) *H2 = I_2x2;
							 | 
						
					
						
							
								
									
										
										
										
											2013-06-21 00:05:24 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								      return l - x;
							 | 
						
					
						
							
								
									
										
										
										
											2013-06-11 22:35:22 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  }
							 | 
						
					
						
							
								
									
										
										
										
											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 = Point2>
							 | 
						
					
						
							
								
									
										
										
										
											2022-12-23 06:25:48 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  class GenericPrior: public NoiseModelFactorN<VALUE> {
							 | 
						
					
						
							
								
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  public:
							 | 
						
					
						
							
								
									
										
										
										
											2022-12-23 06:25:48 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    typedef NoiseModelFactorN<VALUE> Base;  ///< base class
							 | 
						
					
						
							
								
									
										
										
										
											2012-05-22 04:54:40 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    typedef GenericPrior<VALUE> This;
							 | 
						
					
						
							
								
									
										
										
										
											2023-01-18 06:05:12 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    typedef std::shared_ptr<GenericPrior<VALUE> > shared_ptr;
							 | 
						
					
						
							
								
									
										
										
										
											2012-02-06 08:44:25 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    typedef VALUE Pose; ///< shortcut to Pose type
							 | 
						
					
						
							
								
									
										
										
										
											2023-01-07 08:29:15 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
									
							 | 
						
					
						
							
								
									
										
										
										
											2023-01-11 08:15:06 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    // Provide access to the Matrix& version of evaluateError:
							 | 
						
					
						
							
								
									
										
										
										
											2023-01-07 08:29:15 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    using Base::evaluateError;
							 | 
						
					
						
							
								
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2012-02-06 08:44:25 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    Pose measured_; ///< prior mean
							 | 
						
					
						
							
								
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    /// Create generic prior
							 | 
						
					
						
							
								
									
										
										
										
											2012-02-19 09:02:07 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    GenericPrior(const Pose& z, const SharedNoiseModel& model, Key key) :
							 | 
						
					
						
							
								
									
										
										
										
											2012-02-06 08:44:25 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      Base(model, key), measured_(z) {
							 | 
						
					
						
							
								
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    /// Return error and optional derivative
							 | 
						
					
						
							
								
									
										
										
										
											2023-01-07 08:29:15 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    Vector evaluateError(const Pose& x, OptionalMatrixType H) const override {
							 | 
						
					
						
							
								
									
										
										
										
											2023-01-07 09:14:02 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								      return (simulated2D::prior(x, H) - measured_);
							 | 
						
					
						
							
								
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2021-01-29 12:02:13 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    ~GenericPrior() override {}
							 | 
						
					
						
							
								
									
										
										
										
											2012-05-22 04:54:40 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    /// @return a deep copy of this factor
							 | 
						
					
						
							
								
									
										
										
										
											2020-07-26 15:57:54 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    gtsam::NonlinearFactor::shared_ptr clone() const override {
							 | 
						
					
						
							
								
									
										
										
										
											2023-01-18 06:39:55 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								      return std::static_pointer_cast<gtsam::NonlinearFactor>(
							 | 
						
					
						
							
								
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								          gtsam::NonlinearFactor::shared_ptr(new This(*this))); }
							 | 
						
					
						
							
								
									
										
										
										
											2012-05-22 04:54:40 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  private:
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    /// Default constructor
							 | 
						
					
						
							
								
									
										
										
										
											2012-05-22 04:54:40 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    GenericPrior() { }
							 | 
						
					
						
							
								
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2024-12-27 12:44:00 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								#if GTSAM_ENABLE_BOOST_SERIALIZATION    ///
							 | 
						
					
						
							
								
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    /// Serialization function
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    friend class boost::serialization::access;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    template<class ARCHIVE>
							 | 
						
					
						
							
								
									
										
										
										
											2015-03-06 23:12:09 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
							 | 
						
					
						
							
								
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
							 | 
						
					
						
							
								
									
										
										
										
											2012-02-06 08:44:25 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      ar & BOOST_SERIALIZATION_NVP(measured_);
							 | 
						
					
						
							
								
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    }
							 | 
						
					
						
							
								
									
										
										
										
											2023-01-19 04:03:30 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								#endif
							 | 
						
					
						
							
								
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  };
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  /**
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								   * Binary factor simulating "odometry" between two Vectors
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								   */
							 | 
						
					
						
							
								
									
										
										
										
											2012-02-07 07:32:59 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  template<class VALUE = Point2>
							 | 
						
					
						
							
								
									
										
										
										
											2022-12-23 06:25:48 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  class GenericOdometry: public NoiseModelFactorN<VALUE, VALUE> {
							 | 
						
					
						
							
								
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  public:
							 | 
						
					
						
							
								
									
										
										
										
											2022-12-23 06:25:48 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    typedef NoiseModelFactorN<VALUE, VALUE> Base; ///< base class
							 | 
						
					
						
							
								
									
										
										
										
											2012-05-22 04:54:40 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    typedef GenericOdometry<VALUE> This;
							 | 
						
					
						
							
								
									
										
										
										
											2023-01-18 06:05:12 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    typedef std::shared_ptr<GenericOdometry<VALUE> > shared_ptr;
							 | 
						
					
						
							
								
									
										
										
										
											2012-02-06 08:44:25 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    typedef VALUE Pose; ///< shortcut to Pose type
							 | 
						
					
						
							
								
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2023-01-11 08:15:06 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    // Provide access to the Matrix& version of evaluateError:
							 | 
						
					
						
							
								
									
										
										
										
											2023-01-07 08:29:15 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    using Base::evaluateError;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2012-02-06 08:44:25 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    Pose measured_; ///< odometry measurement
							 | 
						
					
						
							
								
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    /// Create odometry
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-03 00:18:40 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    GenericOdometry(const Pose& measured, const SharedNoiseModel& model, Key i1, Key i2) :
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								          Base(model, i1, i2), measured_(measured) {
							 | 
						
					
						
							
								
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    /// Evaluate error and optionally return derivatives
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    Vector evaluateError(const Pose& x1, const Pose& x2,
							 | 
						
					
						
							
								
									
										
										
										
											2023-01-07 08:29:15 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								        OptionalMatrixType H1, OptionalMatrixType H2) const override {
							 | 
						
					
						
							
								
									
										
										
										
											2016-06-06 14:52:04 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								      return (odo(x1, x2, H1, H2) - measured_);
							 | 
						
					
						
							
								
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2021-01-29 12:02:13 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    ~GenericOdometry() override {}
							 | 
						
					
						
							
								
									
										
										
										
											2012-05-22 04:54:40 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    /// @return a deep copy of this factor
							 | 
						
					
						
							
								
									
										
										
										
											2020-07-26 15:57:54 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    gtsam::NonlinearFactor::shared_ptr clone() const override {
							 | 
						
					
						
							
								
									
										
										
										
											2023-01-18 06:39:55 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								      return std::static_pointer_cast<gtsam::NonlinearFactor>(
							 | 
						
					
						
							
								
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								          gtsam::NonlinearFactor::shared_ptr(new This(*this))); }
							 | 
						
					
						
							
								
									
										
										
										
											2012-05-22 04:54:40 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  private:
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    /// Default constructor
							 | 
						
					
						
							
								
									
										
										
										
											2012-05-22 04:54:40 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    GenericOdometry() { }
							 | 
						
					
						
							
								
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2024-12-27 12:44:00 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								#if GTSAM_ENABLE_BOOST_SERIALIZATION    ///
							 | 
						
					
						
							
								
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    /// Serialization function
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    friend class boost::serialization::access;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    template<class ARCHIVE>
							 | 
						
					
						
							
								
									
										
										
										
											2015-03-06 23:12:09 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
							 | 
						
					
						
							
								
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
							 | 
						
					
						
							
								
									
										
										
										
											2012-02-06 08:44:25 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      ar & BOOST_SERIALIZATION_NVP(measured_);
							 | 
						
					
						
							
								
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    }
							 | 
						
					
						
							
								
									
										
										
										
											2023-01-19 07:25:07 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								#endif
							 | 
						
					
						
							
								
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  };
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  /**
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								   * Binary factor simulating "measurement" between two Vectors
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								   */
							 | 
						
					
						
							
								
									
										
										
										
											2012-02-06 08:44:25 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  template<class POSE, class LANDMARK>
							 | 
						
					
						
							
								
									
										
										
										
											2022-12-23 06:25:48 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  class GenericMeasurement: public NoiseModelFactorN<POSE, LANDMARK> {
							 | 
						
					
						
							
								
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  public:
							 | 
						
					
						
							
								
									
										
										
										
											2022-12-23 06:25:48 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    typedef NoiseModelFactorN<POSE, LANDMARK> Base;  ///< base class
							 | 
						
					
						
							
								
									
										
										
										
											2012-05-22 04:54:40 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    typedef GenericMeasurement<POSE, LANDMARK> This;
							 | 
						
					
						
							
								
									
										
										
										
											2023-01-18 06:05:12 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    typedef std::shared_ptr<GenericMeasurement<POSE, LANDMARK> > shared_ptr;
							 | 
						
					
						
							
								
									
										
										
										
											2012-02-06 08:44:25 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    typedef POSE Pose; ///< shortcut to Pose type
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    typedef LANDMARK Landmark; ///< shortcut to Landmark type
							 | 
						
					
						
							
								
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2023-01-11 08:15:06 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    // Provide access to the Matrix& version of evaluateError:
							 | 
						
					
						
							
								
									
										
										
										
											2023-01-07 08:29:15 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    using Base::evaluateError;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2012-02-07 07:32:59 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    Landmark measured_; ///< Measurement
							 | 
						
					
						
							
								
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    /// Create measurement factor
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-03 00:18:40 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    GenericMeasurement(const Landmark& measured, const SharedNoiseModel& model, Key i, Key j) :
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								          Base(model, i, j), measured_(measured) {
							 | 
						
					
						
							
								
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    /// Evaluate error and optionally return derivatives
							 | 
						
					
						
							
								
									
										
										
										
											2012-02-06 08:44:25 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    Vector evaluateError(const Pose& x1, const Landmark& x2,
							 | 
						
					
						
							
								
									
										
										
										
											2023-01-07 08:29:15 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								        OptionalMatrixType H1, OptionalMatrixType H2) const override {
							 | 
						
					
						
							
								
									
										
										
										
											2016-06-06 14:52:04 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								      return (mea(x1, x2, H1, H2) - measured_);
							 | 
						
					
						
							
								
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2021-01-29 12:02:13 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    ~GenericMeasurement() override {}
							 | 
						
					
						
							
								
									
										
										
										
											2012-05-22 04:54:40 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    /// @return a deep copy of this factor
							 | 
						
					
						
							
								
									
										
										
										
											2020-07-26 15:57:54 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    gtsam::NonlinearFactor::shared_ptr clone() const override {
							 | 
						
					
						
							
								
									
										
										
										
											2023-01-18 06:39:55 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								      return std::static_pointer_cast<gtsam::NonlinearFactor>(
							 | 
						
					
						
							
								
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								          gtsam::NonlinearFactor::shared_ptr(new This(*this))); }
							 | 
						
					
						
							
								
									
										
										
										
											2012-05-22 04:54:40 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  private:
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    /// Default constructor
							 | 
						
					
						
							
								
									
										
										
										
											2012-05-22 04:54:40 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    GenericMeasurement() { }
							 | 
						
					
						
							
								
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2024-12-27 12:44:00 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								#if GTSAM_ENABLE_BOOST_SERIALIZATION    ///
							 | 
						
					
						
							
								
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    /// Serialization function
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    friend class boost::serialization::access;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    template<class ARCHIVE>
							 | 
						
					
						
							
								
									
										
										
										
											2015-03-06 23:12:09 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
							 | 
						
					
						
							
								
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
							 | 
						
					
						
							
								
									
										
										
										
											2012-02-06 08:44:25 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      ar & BOOST_SERIALIZATION_NVP(measured_);
							 | 
						
					
						
							
								
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    }
							 | 
						
					
						
							
								
									
										
										
										
											2023-01-19 07:25:07 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								#endif
							 | 
						
					
						
							
								
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  };
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  /** Typedefs for regular use */
							 | 
						
					
						
							
								
									
										
										
										
											2012-02-06 08:44:25 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  typedef GenericPrior<Point2> Prior;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  typedef GenericOdometry<Point2> Odometry;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  typedef GenericMeasurement<Point2, Point2> Measurement;
							 | 
						
					
						
							
								
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // Specialization of a graph for this example domain
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  // TODO: add functions to add factor types
							 | 
						
					
						
							
								
									
										
										
										
											2012-02-04 01:18:32 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  class Graph : public NonlinearFactorGraph {
							 | 
						
					
						
							
								
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  public:
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    Graph() {}
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  };
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								} // namespace simulated2D
							 | 
						
					
						
							
								
									
										
										
										
											2014-12-22 05:02:06 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/// traits
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								namespace gtsam {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								template<class POSE, class LANDMARK>
							 | 
						
					
						
							
								
									
										
										
										
											2014-12-26 23:47:51 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								struct traits<simulated2D::GenericMeasurement<POSE, LANDMARK> > : Testable<
							 | 
						
					
						
							
								
									
										
										
										
											2014-12-22 05:02:06 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    simulated2D::GenericMeasurement<POSE, LANDMARK> > {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								};
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								template<>
							 | 
						
					
						
							
								
									
										
										
										
											2014-12-26 23:47:51 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								struct traits<simulated2D::Values> : public Testable<simulated2D::Values> {
							 | 
						
					
						
							
								
									
										
										
										
											2014-12-22 05:02:06 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								};
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								}
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 |