Merge pull request #489 from borglab/feature/remove_point_type
Remove GTSAM_DEFINE_POINTS_TO_VECTORSrelease/4.3a0
						commit
						838c5df471
					
				| 
						 | 
				
			
			@ -79,7 +79,6 @@ option(GTSAM_WITH_EIGEN_MKL_OPENMP       "Eigen, when using Intel MKL, will also
 | 
			
		|||
option(GTSAM_THROW_CHEIRALITY_EXCEPTION  "Throw exception when a triangulated point is behind a camera" ON)
 | 
			
		||||
option(GTSAM_BUILD_PYTHON                "Enable/Disable building & installation of Python module with pybind11" OFF)
 | 
			
		||||
option(GTSAM_ALLOW_DEPRECATED_SINCE_V41  "Allow use of methods/functions deprecated in GTSAM 4.1" ON)
 | 
			
		||||
option(GTSAM_TYPEDEF_POINTS_TO_VECTORS   "Typedef Point2 and Point3 to Eigen::Vector equivalents" OFF)
 | 
			
		||||
option(GTSAM_SUPPORT_NESTED_DISSECTION   "Support Metis-based nested dissection" ON)
 | 
			
		||||
option(GTSAM_TANGENT_PREINTEGRATION      "Use new ImuFactor with integration on tangent space" ON)
 | 
			
		||||
if(NOT MSVC AND NOT XCODE_VERSION)
 | 
			
		||||
| 
						 | 
				
			
			@ -114,10 +113,6 @@ if(GTSAM_INSTALL_MATLAB_TOOLBOX AND NOT BUILD_SHARED_LIBS)
 | 
			
		|||
endif()
 | 
			
		||||
 | 
			
		||||
if(GTSAM_BUILD_PYTHON)
 | 
			
		||||
    if (NOT GTSAM_TYPEDEF_POINTS_TO_VECTORS)
 | 
			
		||||
        message(FATAL_ERROR "GTSAM_BUILD_PYTHON requires GTSAM_TYPEDEF_POINTS_TO_VECTORS to be enabled but it is not.")
 | 
			
		||||
    endif()
 | 
			
		||||
 | 
			
		||||
    if(GTSAM_UNSTABLE_BUILD_PYTHON)
 | 
			
		||||
        if (NOT GTSAM_BUILD_UNSTABLE)
 | 
			
		||||
            message(WARNING "GTSAM_UNSTABLE_BUILD_PYTHON requires the unstable module to be enabled.")
 | 
			
		||||
| 
						 | 
				
			
			@ -586,7 +581,6 @@ print_enabled_config(${GTSAM_ENABLE_CONSISTENCY_CHECKS}   "Runtime consistency c
 | 
			
		|||
print_enabled_config(${GTSAM_ROT3_EXPMAP}                 "Rot3 retract is full ExpMap     ")
 | 
			
		||||
print_enabled_config(${GTSAM_POSE3_EXPMAP}                "Pose3 retract is full ExpMap    ")
 | 
			
		||||
print_enabled_config(${GTSAM_ALLOW_DEPRECATED_SINCE_V41}  "Allow features deprecated in GTSAM 4.1")
 | 
			
		||||
print_enabled_config(${GTSAM_TYPEDEF_POINTS_TO_VECTORS}   "Point3 is typedef to Vector3    ")
 | 
			
		||||
print_enabled_config(${GTSAM_SUPPORT_NESTED_DISSECTION}   "Metis-based Nested Dissection   ")
 | 
			
		||||
print_enabled_config(${GTSAM_TANGENT_PREINTEGRATION}      "Use tangent-space preintegration")
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -72,9 +72,6 @@
 | 
			
		|||
// Make sure dependent projects that want it can see deprecated functions
 | 
			
		||||
#cmakedefine GTSAM_ALLOW_DEPRECATED_SINCE_V41
 | 
			
		||||
 | 
			
		||||
// Publish flag about Eigen typedef
 | 
			
		||||
#cmakedefine GTSAM_TYPEDEF_POINTS_TO_VECTORS
 | 
			
		||||
 | 
			
		||||
// Support Metis-based nested dissection
 | 
			
		||||
#cmakedefine GTSAM_SUPPORT_NESTED_DISSECTION
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -50,37 +50,6 @@ double distance2(const Point2& p, const Point2& q, OptionalJacobian<1, 2> H1,
 | 
			
		|||
  }
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
#ifndef GTSAM_TYPEDEF_POINTS_TO_VECTORS
 | 
			
		||||
 | 
			
		||||
/* ************************************************************************* */
 | 
			
		||||
void Point2::print(const string& s) const {
 | 
			
		||||
  cout << s << *this << endl;
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
/* ************************************************************************* */
 | 
			
		||||
bool Point2::equals(const Point2& q, double tol) const {
 | 
			
		||||
  return (std::abs(x() - q.x()) < tol && std::abs(y() - q.y()) < tol);
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
/* ************************************************************************* */
 | 
			
		||||
double Point2::norm(OptionalJacobian<1,2> H) const {
 | 
			
		||||
  return gtsam::norm2(*this, H);
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
/* ************************************************************************* */
 | 
			
		||||
double Point2::distance(const Point2& point, OptionalJacobian<1,2> H1,
 | 
			
		||||
    OptionalJacobian<1,2> H2) const {
 | 
			
		||||
  return gtsam::distance2(*this, point, H1, H2);
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
/* ************************************************************************* */
 | 
			
		||||
ostream &operator<<(ostream &os, const Point2& p) {
 | 
			
		||||
  os << '(' << p.x() << ", " << p.y() << ')';
 | 
			
		||||
  return os;
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
#endif // GTSAM_TYPEDEF_POINTS_TO_VECTORS
 | 
			
		||||
 | 
			
		||||
/* ************************************************************************* */
 | 
			
		||||
// Math inspired by http://paulbourke.net/geometry/circlesphere/
 | 
			
		||||
boost::optional<Point2> circleCircleIntersection(double R_d, double r_d,
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -22,111 +22,9 @@
 | 
			
		|||
 | 
			
		||||
namespace gtsam {
 | 
			
		||||
 | 
			
		||||
#ifdef GTSAM_TYPEDEF_POINTS_TO_VECTORS
 | 
			
		||||
 | 
			
		||||
  /// As of GTSAM 4, in order to make GTSAM more lean,
 | 
			
		||||
  /// it is now possible to just typedef Point2 to Vector2
 | 
			
		||||
  typedef Vector2 Point2;
 | 
			
		||||
 | 
			
		||||
#else
 | 
			
		||||
 | 
			
		||||
/**
 | 
			
		||||
 * A 2D point
 | 
			
		||||
 * Complies with the Testable Concept
 | 
			
		||||
 * Functional, so no set functions: once created, a point is constant.
 | 
			
		||||
 * @addtogroup geometry
 | 
			
		||||
 * \nosubgrouping
 | 
			
		||||
 */
 | 
			
		||||
class Point2 : public Vector2 {
 | 
			
		||||
private:
 | 
			
		||||
 | 
			
		||||
public:
 | 
			
		||||
  enum { dimension = 2 };
 | 
			
		||||
  /// @name Standard Constructors
 | 
			
		||||
  /// @{
 | 
			
		||||
 | 
			
		||||
  /// default constructor
 | 
			
		||||
  Point2() {}
 | 
			
		||||
 | 
			
		||||
  using Vector2::Vector2;
 | 
			
		||||
 | 
			
		||||
  /// @}
 | 
			
		||||
  /// @name Advanced Constructors
 | 
			
		||||
  /// @{
 | 
			
		||||
 | 
			
		||||
  /// construct from 2D vector
 | 
			
		||||
  explicit Point2(const Vector2& v):Vector2(v) {}
 | 
			
		||||
  /// @}
 | 
			
		||||
  /// @name Testable
 | 
			
		||||
  /// @{
 | 
			
		||||
 | 
			
		||||
  /// print with optional string
 | 
			
		||||
  GTSAM_EXPORT void print(const std::string& s = "") const;
 | 
			
		||||
 | 
			
		||||
  /// equals with an tolerance, prints out message if unequal
 | 
			
		||||
  GTSAM_EXPORT bool equals(const Point2& q, double tol = 1e-9) const;
 | 
			
		||||
 | 
			
		||||
  /// @}
 | 
			
		||||
  /// @name Group
 | 
			
		||||
  /// @{
 | 
			
		||||
 | 
			
		||||
  /// identity
 | 
			
		||||
  inline static Point2 identity() {return Point2(0,0);}
 | 
			
		||||
 | 
			
		||||
  /// @}
 | 
			
		||||
  /// @name Vector Space
 | 
			
		||||
  /// @{
 | 
			
		||||
 | 
			
		||||
  /** creates a unit vector */
 | 
			
		||||
  Point2 unit() const { return *this/norm(); }
 | 
			
		||||
 | 
			
		||||
  /** norm of point, with derivative */
 | 
			
		||||
  GTSAM_EXPORT double norm(OptionalJacobian<1,2> H = boost::none) const;
 | 
			
		||||
 | 
			
		||||
  /** distance between two points */
 | 
			
		||||
  GTSAM_EXPORT double distance(const Point2& p2, OptionalJacobian<1,2> H1 = boost::none,
 | 
			
		||||
      OptionalJacobian<1,2> H2 = boost::none) const;
 | 
			
		||||
 | 
			
		||||
  /// @}
 | 
			
		||||
  /// @name Standard Interface
 | 
			
		||||
  /// @{
 | 
			
		||||
 | 
			
		||||
  /// equality
 | 
			
		||||
  inline bool operator ==(const Point2& q) const {return x()==q.x() && y()==q.y();}
 | 
			
		||||
 | 
			
		||||
  /// get x
 | 
			
		||||
  inline double x() const {return (*this)[0];}
 | 
			
		||||
 | 
			
		||||
  /// get y
 | 
			
		||||
  inline double y() const {return (*this)[1];}
 | 
			
		||||
 | 
			
		||||
  /// return vectorized form (column-wise).
 | 
			
		||||
  const Vector2& vector() const { return *this; }
 | 
			
		||||
 | 
			
		||||
  /// @}
 | 
			
		||||
 | 
			
		||||
  /// Streaming
 | 
			
		||||
  GTSAM_EXPORT friend std::ostream &operator<<(std::ostream &os, const Point2& p);
 | 
			
		||||
 | 
			
		||||
 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_BASE_OBJECT_NVP(Vector2);}
 | 
			
		||||
 | 
			
		||||
 /// @}
 | 
			
		||||
};
 | 
			
		||||
 | 
			
		||||
template<>
 | 
			
		||||
struct traits<Point2> : public internal::VectorSpace<Point2> {
 | 
			
		||||
};
 | 
			
		||||
 | 
			
		||||
#endif // GTSAM_TYPEDEF_POINTS_TO_VECTORS
 | 
			
		||||
/// As of GTSAM 4, in order to make GTSAM more lean,
 | 
			
		||||
/// it is now possible to just typedef Point2 to Vector2
 | 
			
		||||
typedef Vector2 Point2;
 | 
			
		||||
 | 
			
		||||
/// Distance of the point from the origin, with Jacobian
 | 
			
		||||
GTSAM_EXPORT double norm2(const Point2& p, OptionalJacobian<1, 2> H = boost::none);
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -22,47 +22,6 @@ using namespace std;
 | 
			
		|||
 | 
			
		||||
namespace gtsam {
 | 
			
		||||
 | 
			
		||||
#ifndef GTSAM_TYPEDEF_POINTS_TO_VECTORS
 | 
			
		||||
bool Point3::equals(const Point3 &q, double tol) const {
 | 
			
		||||
  return (std::abs(x() - q.x()) < tol && std::abs(y() - q.y()) < tol &&
 | 
			
		||||
          std::abs(z() - q.z()) < tol);
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
void Point3::print(const string& s) const {
 | 
			
		||||
  cout << s << *this << endl;
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
/* ************************************************************************* */
 | 
			
		||||
double Point3::distance(const Point3 &q, OptionalJacobian<1, 3> H1,
 | 
			
		||||
                        OptionalJacobian<1, 3> H2) const {
 | 
			
		||||
  return gtsam::distance3(*this,q,H1,H2);
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
double Point3::norm(OptionalJacobian<1,3> H) const {
 | 
			
		||||
  return gtsam::norm3(*this, H);
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
Point3 Point3::normalized(OptionalJacobian<3,3> H) const {
 | 
			
		||||
  return gtsam::normalize(*this, H);
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
Point3 Point3::cross(const Point3 &q, OptionalJacobian<3, 3> H1,
 | 
			
		||||
                     OptionalJacobian<3, 3> H2) const {
 | 
			
		||||
  return gtsam::cross(*this, q, H1, H2);
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
double Point3::dot(const Point3 &q, OptionalJacobian<1, 3> H1,
 | 
			
		||||
                   OptionalJacobian<1, 3> H2) const {
 | 
			
		||||
  return gtsam::dot(*this, q, H1, H2);
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
/* ************************************************************************* */
 | 
			
		||||
ostream &operator<<(ostream &os, const Point3& p) {
 | 
			
		||||
  os << '[' << p.x() << ", " << p.y() << ", " << p.z() << "]'";
 | 
			
		||||
  return os;
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
#endif
 | 
			
		||||
/* ************************************************************************* */
 | 
			
		||||
double distance3(const Point3 &p1, const Point3 &q, OptionalJacobian<1, 3> H1,
 | 
			
		||||
                 OptionalJacobian<1, 3> H2) {
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -29,106 +29,9 @@
 | 
			
		|||
 | 
			
		||||
namespace gtsam {
 | 
			
		||||
 | 
			
		||||
#ifdef GTSAM_TYPEDEF_POINTS_TO_VECTORS
 | 
			
		||||
 | 
			
		||||
  /// As of GTSAM 4, in order to make GTSAM more lean,
 | 
			
		||||
  /// it is now possible to just typedef Point3 to Vector3
 | 
			
		||||
  typedef Vector3 Point3;
 | 
			
		||||
 | 
			
		||||
#else
 | 
			
		||||
 | 
			
		||||
/**
 | 
			
		||||
   * A 3D point is just a Vector3 with some additional methods
 | 
			
		||||
   * @addtogroup geometry
 | 
			
		||||
   * \nosubgrouping
 | 
			
		||||
   */
 | 
			
		||||
class Point3 : public Vector3 {
 | 
			
		||||
 | 
			
		||||
  public:
 | 
			
		||||
 | 
			
		||||
    enum { dimension = 3 };
 | 
			
		||||
 | 
			
		||||
    /// @name Standard Constructors
 | 
			
		||||
    /// @{
 | 
			
		||||
 | 
			
		||||
    using Vector3::Vector3;
 | 
			
		||||
 | 
			
		||||
    /// @}
 | 
			
		||||
    /// @name Testable
 | 
			
		||||
    /// @{
 | 
			
		||||
 | 
			
		||||
    /** print with optional string */
 | 
			
		||||
	GTSAM_EXPORT void print(const std::string& s = "") const;
 | 
			
		||||
 | 
			
		||||
    /** equals with an tolerance */
 | 
			
		||||
	GTSAM_EXPORT bool equals(const Point3& p, double tol = 1e-9) const;
 | 
			
		||||
 | 
			
		||||
    /// @}
 | 
			
		||||
    /// @name Group
 | 
			
		||||
    /// @{
 | 
			
		||||
 | 
			
		||||
    /// identity for group operation
 | 
			
		||||
    inline static Point3 identity() { return Point3(0.0, 0.0, 0.0); }
 | 
			
		||||
 | 
			
		||||
    /// @}
 | 
			
		||||
    /// @name Vector Space
 | 
			
		||||
    /// @{
 | 
			
		||||
 | 
			
		||||
    /** distance between two points */
 | 
			
		||||
	GTSAM_EXPORT double distance(const Point3& p2, OptionalJacobian<1, 3> H1 = boost::none,
 | 
			
		||||
                    OptionalJacobian<1, 3> H2 = boost::none) const;
 | 
			
		||||
 | 
			
		||||
    /** Distance of the point from the origin, with Jacobian */
 | 
			
		||||
	GTSAM_EXPORT double norm(OptionalJacobian<1,3> H = boost::none) const;
 | 
			
		||||
 | 
			
		||||
    /** normalize, with optional Jacobian */
 | 
			
		||||
	GTSAM_EXPORT Point3 normalized(OptionalJacobian<3, 3> H = boost::none) const;
 | 
			
		||||
 | 
			
		||||
    /** cross product @return this x q */
 | 
			
		||||
	GTSAM_EXPORT Point3 cross(const Point3 &q, OptionalJacobian<3, 3> H_p = boost::none, //
 | 
			
		||||
                                  OptionalJacobian<3, 3> H_q = boost::none) const;
 | 
			
		||||
 | 
			
		||||
    /** dot product @return this * q*/
 | 
			
		||||
	GTSAM_EXPORT double dot(const Point3 &q, OptionalJacobian<1, 3> H_p = boost::none, //
 | 
			
		||||
                                OptionalJacobian<1, 3> H_q = boost::none) const;
 | 
			
		||||
 | 
			
		||||
    /// @}
 | 
			
		||||
    /// @name Standard Interface
 | 
			
		||||
    /// @{
 | 
			
		||||
 | 
			
		||||
    /// return as Vector3
 | 
			
		||||
    const Vector3& vector() const { return *this; }
 | 
			
		||||
 | 
			
		||||
    /// get x
 | 
			
		||||
    inline double x() const {return (*this)[0];}
 | 
			
		||||
 | 
			
		||||
    /// get y
 | 
			
		||||
    inline double y() const {return (*this)[1];}
 | 
			
		||||
 | 
			
		||||
    /// get z
 | 
			
		||||
    inline double z() const {return (*this)[2];}
 | 
			
		||||
 | 
			
		||||
    /// @}
 | 
			
		||||
 | 
			
		||||
    /// Output stream operator
 | 
			
		||||
    GTSAM_EXPORT friend std::ostream &operator<<(std::ostream &os, const Point3& p);
 | 
			
		||||
 | 
			
		||||
   private:
 | 
			
		||||
    /** Serialization function */
 | 
			
		||||
    friend class boost::serialization::access;
 | 
			
		||||
    template<class ARCHIVE>
 | 
			
		||||
    void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
 | 
			
		||||
      ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Vector3);
 | 
			
		||||
    }
 | 
			
		||||
  };
 | 
			
		||||
 | 
			
		||||
template<>
 | 
			
		||||
struct traits<Point3> : public internal::VectorSpace<Point3> {};
 | 
			
		||||
 | 
			
		||||
template<>
 | 
			
		||||
struct traits<const Point3> : public internal::VectorSpace<Point3> {};
 | 
			
		||||
 | 
			
		||||
#endif // GTSAM_TYPEDEF_POINTS_TO_VECTORS
 | 
			
		||||
/// As of GTSAM 4, in order to make GTSAM more lean,
 | 
			
		||||
/// it is now possible to just typedef Point3 to Vector3
 | 
			
		||||
typedef Vector3 Point3;
 | 
			
		||||
 | 
			
		||||
// Convenience typedef
 | 
			
		||||
typedef std::pair<Point3, Point3> Point3Pair;
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -237,16 +237,6 @@ TEST( Point2, circleCircleIntersection) {
 | 
			
		|||
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
/* ************************************************************************* */
 | 
			
		||||
#ifndef GTSAM_TYPEDEF_POINTS_TO_VECTORS
 | 
			
		||||
TEST( Point2, stream) {
 | 
			
		||||
  Point2 p(1, 2);
 | 
			
		||||
  std::ostringstream os;
 | 
			
		||||
  os << p;
 | 
			
		||||
  EXPECT(os.str() == "(1, 2)");
 | 
			
		||||
}
 | 
			
		||||
#endif
 | 
			
		||||
 | 
			
		||||
/* ************************************************************************* */
 | 
			
		||||
int main () {
 | 
			
		||||
  TestResult tr;
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -153,16 +153,6 @@ TEST( Point3, cross2) {
 | 
			
		|||
  }
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
/* ************************************************************************* */
 | 
			
		||||
#ifndef GTSAM_TYPEDEF_POINTS_TO_VECTORS
 | 
			
		||||
TEST( Point3, stream) {
 | 
			
		||||
  Point3 p(1, 2, -3);
 | 
			
		||||
  std::ostringstream os;
 | 
			
		||||
  os << p;
 | 
			
		||||
  EXPECT(os.str() == "[1, 2, -3]'");
 | 
			
		||||
}
 | 
			
		||||
#endif
 | 
			
		||||
 | 
			
		||||
//*************************************************************************
 | 
			
		||||
TEST (Point3, normalize) {
 | 
			
		||||
  Matrix actualH;
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -864,11 +864,7 @@ TEST( Pose3, stream)
 | 
			
		|||
  os << T;
 | 
			
		||||
 | 
			
		||||
  string expected;
 | 
			
		||||
#ifdef GTSAM_TYPEDEF_POINTS_TO_VECTORS
 | 
			
		||||
  expected = "R: [\n\t1, 0, 0;\n\t0, 1, 0;\n\t0, 0, 1\n]\nt: 0\n0\n0";;
 | 
			
		||||
#else
 | 
			
		||||
  expected = "R: [\n\t1, 0, 0;\n\t0, 1, 0;\n\t0, 0, 1\n]\nt: [0, 0, 0]'";
 | 
			
		||||
#endif
 | 
			
		||||
 | 
			
		||||
  EXPECT(os.str() == expected);
 | 
			
		||||
}
 | 
			
		||||
| 
						 | 
				
			
			@ -1043,13 +1039,9 @@ TEST(Pose3, print) {
 | 
			
		|||
  // Add expected rotation
 | 
			
		||||
  expected << "R: [\n\t1, 0, 0;\n\t0, 1, 0;\n\t0, 0, 1\n]\n";
 | 
			
		||||
 | 
			
		||||
#ifdef GTSAM_TYPEDEF_POINTS_TO_VECTORS
 | 
			
		||||
  expected << "t: 1\n"
 | 
			
		||||
              "2\n"
 | 
			
		||||
              "3\n";
 | 
			
		||||
#else
 | 
			
		||||
  expected << "t: [" << translation.x() << ", " << translation.y() << ", " << translation.z() << "]'\n";
 | 
			
		||||
#endif
 | 
			
		||||
 | 
			
		||||
  // reset cout to the original stream
 | 
			
		||||
  std::cout.rdbuf(oldbuf);
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -215,11 +215,7 @@ TEST(NavState, Stream)
 | 
			
		|||
  os << state;
 | 
			
		||||
 | 
			
		||||
  string expected;
 | 
			
		||||
#ifdef GTSAM_TYPEDEF_POINTS_TO_VECTORS
 | 
			
		||||
  expected = "R: [\n\t1, 0, 0;\n\t0, 1, 0;\n\t0, 0, 1\n]\np: 0\n0\n0\nv: 0\n0\n0";
 | 
			
		||||
#else
 | 
			
		||||
  expected = "R: [\n\t1, 0, 0;\n\t0, 1, 0;\n\t0, 0, 1\n]\np: [0, 0, 0]'\nv: [0, 0, 0]'";
 | 
			
		||||
#endif
 | 
			
		||||
 | 
			
		||||
  EXPECT(os.str() == expected);
 | 
			
		||||
}
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -75,30 +75,6 @@ inline Unit3_ unrotate(const Rot3_& x, const Unit3_& p) {
 | 
			
		|||
  return Unit3_(x, &Rot3::unrotate, p);
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
#ifndef GTSAM_TYPEDEF_POINTS_TO_VECTORS
 | 
			
		||||
namespace internal {
 | 
			
		||||
// define a rotate and unrotate for Vector3
 | 
			
		||||
inline Vector3 rotate(const Rot3& R, const Vector3& v,
 | 
			
		||||
               OptionalJacobian<3, 3> H1 = boost::none,
 | 
			
		||||
               OptionalJacobian<3, 3> H2 = boost::none) {
 | 
			
		||||
  return R.rotate(v, H1, H2);
 | 
			
		||||
}
 | 
			
		||||
inline Vector3 unrotate(const Rot3& R, const Vector3& v,
 | 
			
		||||
                 OptionalJacobian<3, 3> H1 = boost::none,
 | 
			
		||||
                 OptionalJacobian<3, 3> H2 = boost::none) {
 | 
			
		||||
  return R.unrotate(v, H1, H2);
 | 
			
		||||
}
 | 
			
		||||
}  // namespace internal
 | 
			
		||||
inline Expression<Vector3> rotate(const Rot3_& R,
 | 
			
		||||
                                  const Expression<Vector3>& v) {
 | 
			
		||||
  return Expression<Vector3>(internal::rotate, R, v);
 | 
			
		||||
}
 | 
			
		||||
inline Expression<Vector3> unrotate(const Rot3_& R,
 | 
			
		||||
                                    const Expression<Vector3>& v) {
 | 
			
		||||
  return Expression<Vector3>(internal::unrotate, R, v);
 | 
			
		||||
}
 | 
			
		||||
#endif
 | 
			
		||||
 | 
			
		||||
// Projection
 | 
			
		||||
 | 
			
		||||
typedef Expression<Cal3_S2> Cal3_S2_;
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
		Loading…
	
		Reference in New Issue