2013-12-22 03:55:07 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/* ----------------------------------------------------------------------------
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 * Atlanta, Georgia 30332-0415
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 * All Rights Reserved
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 * GTSAM Copyright 2010, Georgia Tech Research Corporation,
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 * See LICENSE for the license information
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 * -------------------------------------------------------------------------- */
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/*
							 | 
						
					
						
							
								
									
										
										
										
											2014-02-23 05:20:28 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 * @file Unit3.h
							 | 
						
					
						
							
								
									
										
										
										
											2013-12-22 03:55:07 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 * @date Feb 02, 2011
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 * @author Can Erdogan
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 * @author Frank Dellaert
							 | 
						
					
						
							
								
									
										
										
										
											2014-01-25 23:07:34 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 * @author Alex Trevor
							 | 
						
					
						
							
								
									
										
										
										
											2014-02-23 05:20:28 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 * @brief Develop a Unit3 class - basically a point on a unit sphere
							 | 
						
					
						
							
								
									
										
										
										
											2013-12-22 03:55:07 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 */
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								#pragma once
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								#include <gtsam/geometry/Point3.h>
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								#include <gtsam/base/DerivedValue.h>
							 | 
						
					
						
							
								
									
										
										
										
											2014-02-13 06:15:02 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								#include <boost/random/mersenne_twister.hpp>
							 | 
						
					
						
							
								
									
										
										
										
											2014-10-15 04:30:13 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								#include <boost/optional.hpp>
							 | 
						
					
						
							
								
									
										
										
										
											2013-12-22 03:55:07 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								namespace gtsam {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								/// Represents a 3D point on a unit sphere.
							 | 
						
					
						
							
								
									
										
										
										
											2014-04-18 10:07:55 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								class GTSAM_EXPORT Unit3: public DerivedValue<Unit3> {
							 | 
						
					
						
							
								
									
										
										
										
											2013-12-22 03:55:07 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								private:
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2014-10-15 04:30:13 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  typedef Eigen::Matrix<double,3,2> Matrix32;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2013-12-22 03:55:07 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  Point3 p_; ///< The location of the point on the unit sphere
							 | 
						
					
						
							
								
									
										
										
										
											2014-10-15 04:30:13 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  mutable boost::optional<Matrix32> B_; ///< Cached basis
							 | 
						
					
						
							
								
									
										
										
										
											2013-12-22 03:55:07 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								public:
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  /// @name Constructors
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  /// @{
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  /// Default constructor
							 | 
						
					
						
							
								
									
										
										
										
											2014-02-23 05:20:28 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  Unit3() :
							 | 
						
					
						
							
								
									
										
										
										
											2013-12-22 03:55:07 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      p_(1.0, 0.0, 0.0) {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  /// Construct from point
							 | 
						
					
						
							
								
									
										
										
										
											2014-02-24 04:52:28 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  explicit Unit3(const Point3& p) :
							 | 
						
					
						
							
								
									
										
										
										
											2013-12-22 03:55:07 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      p_(p / p.norm()) {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  /// Construct from x,y,z
							 | 
						
					
						
							
								
									
										
										
										
											2014-02-23 05:20:28 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  Unit3(double x, double y, double z) :
							 | 
						
					
						
							
								
									
										
										
										
											2013-12-22 03:55:07 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      p_(x, y, z) {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    p_ = p_ / p_.norm();
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2014-01-06 05:25:47 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  /// Named constructor from Point3 with optional Jacobian
							 | 
						
					
						
							
								
									
										
										
										
											2014-02-23 05:20:28 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  static Unit3 FromPoint3(const Point3& point, boost::optional<Matrix&> H =
							 | 
						
					
						
							
								
									
										
										
										
											2014-02-23 03:30:40 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      boost::none);
							 | 
						
					
						
							
								
									
										
										
										
											2014-01-06 05:25:47 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2013-12-27 02:59:15 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  /// Random direction, using boost::uniform_on_sphere
							 | 
						
					
						
							
								
									
										
										
										
											2014-02-24 04:52:28 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  static Unit3 Random(boost::mt19937 & rng);
							 | 
						
					
						
							
								
									
										
										
										
											2013-12-27 02:59:15 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2013-12-22 03:55:07 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  /// @}
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  /// @name Testable
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  /// @{
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  /// The print fuction
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  void print(const std::string& s = std::string()) const;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  /// The equals function with tolerance
							 | 
						
					
						
							
								
									
										
										
										
											2014-02-23 05:20:28 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  bool equals(const Unit3& s, double tol = 1e-9) const {
							 | 
						
					
						
							
								
									
										
										
										
											2013-12-22 03:55:07 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    return p_.equals(s.p_, tol);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  /// @}
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  /// @name Other functionality
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  /// @{
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2014-01-06 05:25:47 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  /**
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								   * Returns the local coordinate frame to tangent plane
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								   * It is a 3*2 matrix [b1 b2] composed of two orthogonal directions
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								   * tangent to the sphere at the current direction.
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								   */
							 | 
						
					
						
							
								
									
										
										
										
											2014-10-15 04:30:13 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								  const Matrix32& basis() const;
							 | 
						
					
						
							
								
									
										
										
										
											2013-12-22 03:55:07 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  /// Return skew-symmetric associated with 3D point on unit sphere
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  Matrix skew() const;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  /// Return unit-norm Point3
							 | 
						
					
						
							
								
									
										
										
										
											2014-02-01 22:31:22 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  const Point3& point3(boost::optional<Matrix&> H = boost::none) const {
							 | 
						
					
						
							
								
									
										
										
										
											2013-12-22 03:55:07 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    if (H)
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      *H = basis();
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    return p_;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2014-02-01 22:31:22 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  /// Return scaled direction as Point3
							 | 
						
					
						
							
								
									
										
										
										
											2014-02-23 05:20:28 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  friend Point3 operator*(double s, const Unit3& d) {
							 | 
						
					
						
							
								
									
										
										
										
											2014-02-23 03:30:40 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    return s * d.p_;
							 | 
						
					
						
							
								
									
										
										
										
											2014-01-25 23:07:34 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2013-12-22 03:55:07 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  /// Signed, vector-valued error between two directions
							 | 
						
					
						
							
								
									
										
										
										
											2014-02-23 05:20:28 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  Vector error(const Unit3& q,
							 | 
						
					
						
							
								
									
										
										
										
											2013-12-22 03:55:07 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      boost::optional<Matrix&> H = boost::none) const;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  /// Distance between two directions
							 | 
						
					
						
							
								
									
										
										
										
											2014-02-23 05:20:28 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  double distance(const Unit3& q,
							 | 
						
					
						
							
								
									
										
										
										
											2013-12-22 03:55:07 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      boost::optional<Matrix&> H = boost::none) const;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  /// @}
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  /// @name Manifold
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  /// @{
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  /// Dimensionality of tangent space = 2 DOF
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  inline static size_t Dim() {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    return 2;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  /// Dimensionality of tangent space = 2 DOF
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  inline size_t dim() const {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    return 2;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2014-01-25 23:07:34 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  enum CoordinatesMode {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    EXPMAP, ///< Use the exponential map to retract
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    RENORM ///< Retract with vector addtion and renormalize.
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  };
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2013-12-22 03:55:07 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  /// The retract function
							 | 
						
					
						
							
								
									
										
										
										
											2014-02-23 05:20:28 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  Unit3 retract(const Vector& v) const;
							 | 
						
					
						
							
								
									
										
										
										
											2013-12-22 03:55:07 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  /// The local coordinates function
							 | 
						
					
						
							
								
									
										
										
										
											2014-02-23 05:20:28 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  Vector localCoordinates(const Unit3& s) const;
							 | 
						
					
						
							
								
									
										
										
										
											2013-12-22 03:55:07 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  /// @}
							 | 
						
					
						
							
								
									
										
										
										
											2014-04-12 03:33:35 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								private:
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  /// @name Advanced Interface
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  /// @{
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  /** Serialization function */
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  friend class boost::serialization::access;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  template<class ARCHIVE>
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    void serialize(ARCHIVE & ar, const unsigned int version) {
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      ar & boost::serialization::make_nvp("Unit3",
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								          boost::serialization::base_object<Value>(*this));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      ar & BOOST_SERIALIZATION_NVP(p_);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								      ar & BOOST_SERIALIZATION_NVP(B_);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    }
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								  /// @}
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2013-12-22 03:55:07 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								};
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								} // namespace gtsam
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 |