StereoPoint2.h
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
19 #pragma once
20 
21 #include <gtsam/geometry/Point2.h>
22 #include <gtsam/base/VectorSpace.h>
23 #include <boost/serialization/nvp.hpp>
24 
25 namespace gtsam {
26 
32 class GTSAM_EXPORT StereoPoint2 {
33 private:
34 
35  double uL_, uR_, v_;
36 
37 public:
38  enum { dimension = 3 };
41 
44  uL_(0), uR_(0), v_(0) {
45  }
46 
48  StereoPoint2(double uL, double uR, double v) :
49  uL_(uL), uR_(uR), v_(v) {
50  }
51 
53  explicit StereoPoint2(const Vector3& v) :
54  uL_(v(0)), uR_(v(1)), v_(v(2)) {}
55 
59 
61  void print(const std::string& s = "") const;
62 
64  bool equals(const StereoPoint2& q, double tol = 1e-9) const {
65  return (std::abs(uL_ - q.uL_) < tol && std::abs(uR_ - q.uR_) < tol
66  && std::abs(v_ - q.v_) < tol);
67  }
68 
72 
74  inline static StereoPoint2 identity() {
75  return StereoPoint2();
76  }
77 
80  return StereoPoint2(-uL_, -uR_, -v_);
81  }
82 
84  inline StereoPoint2 operator +(const Vector3& v) const {
85  return StereoPoint2(uL_ + v[0], uR_ + v[1], v_ + v[2]);
86  }
87 
89  inline StereoPoint2 operator +(const StereoPoint2& b) const {
90  return StereoPoint2(uL_ + b.uL_, uR_ + b.uR_, v_ + b.v_);
91  }
92 
94  inline StereoPoint2 operator -(const StereoPoint2& b) const {
95  return StereoPoint2(uL_ - b.uL_, uR_ - b.uR_, v_ - b.v_);
96  }
97 
101 
103  inline bool operator ==(const StereoPoint2& q) const {return uL_== q.uL_ && uR_==q.uR_ && v_ == q.v_;}
104 
106  inline double uL() const {return uL_;}
107 
109  inline double uR() const {return uR_;}
110 
112  inline double v() const {return v_;}
113 
115  Vector3 vector() const {
116  return Vector3(uL_, uR_, v_);
117  }
118 
120  Point2 point2() const {
121  return Point2(uL_, v_);
122  }
123 
125  Point2 right() const {
126  return Point2(uR_, v_);
127  }
128 
131  inline StereoPoint2 inverse() const { return StereoPoint2()- (*this);}
132  inline StereoPoint2 compose(const StereoPoint2& p1) const { return *this + p1;}
133  inline StereoPoint2 between(const StereoPoint2& p2) const { return p2 - *this; }
134  inline Vector localCoordinates(const StereoPoint2& t2) const { return Logmap(between(t2)); }
135  inline StereoPoint2 retract(const Vector& v) const { return compose(Expmap(v)); }
136  static inline Vector Logmap(const StereoPoint2& p) { return p.vector(); }
137  static inline StereoPoint2 Expmap(const Vector& d) { return StereoPoint2(d(0), d(1), d(2)); }
139 
141  GTSAM_EXPORT friend std::ostream &operator<<(std::ostream &os, const StereoPoint2& p);
142 
143 private:
144 
148 
150  friend class boost::serialization::access;
151  template<class ARCHIVE>
152  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
153  ar & BOOST_SERIALIZATION_NVP(uL_);
154  ar & BOOST_SERIALIZATION_NVP(uR_);
155  ar & BOOST_SERIALIZATION_NVP(v_);
156  }
157 
159 
160 };
161 
162 typedef std::vector<StereoPoint2> StereoPoint2Vector;
163 
164 template<>
165 struct traits<StereoPoint2> : public internal::VectorSpace<StereoPoint2> {};
166 
167 template<>
168 struct traits<const StereoPoint2> : public internal::VectorSpace<StereoPoint2> {};
169 }
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
double uR() const
get uR
Definition: StereoPoint2.h:109
double uL() const
get uL
Definition: StereoPoint2.h:106
std::ostream & operator<<(std::ostream &os, const Dih6 &m)
Definition: testGroup.cpp:109
static StereoPoint2 Expmap(const Vector &d)
Definition: StereoPoint2.h:137
Eigen::Vector3d Vector3
Definition: Vector.h:43
static StereoPoint2 identity()
identity
Definition: StereoPoint2.h:74
VectorSpace provides both Testable and VectorSpaceTraits.
Definition: VectorSpace.h:207
Vector3f p1
Vector2 Point2
Definition: Point2.h:27
ArrayXcf v
Definition: Cwise_arg.cpp:1
Point2 right() const
Definition: StereoPoint2.h:125
Pose2_ Expmap(const Vector3_ &xi)
StereoPoint2 retract(const Vector &v) const
Definition: StereoPoint2.h:135
StereoPoint2 compose(const StereoPoint2 &p1) const
Definition: StereoPoint2.h:132
std::vector< StereoPoint2 > StereoPoint2Vector
Definition: StereoPoint2.h:162
bool operator==(const Matrix &A, const Matrix &B)
Definition: base/Matrix.h:103
StereoPoint2 between(const StereoPoint2 &p2) const
Definition: StereoPoint2.h:133
Point2 point2() const
Definition: StereoPoint2.h:120
StereoPoint2(double uL, double uR, double v)
Definition: StereoPoint2.h:48
void serialize(ARCHIVE &ar, const unsigned int)
Definition: StereoPoint2.h:152
double v() const
get v
Definition: StereoPoint2.h:112
Eigen::VectorXd Vector
Definition: Vector.h:38
StereoPoint2 inverse() const
Definition: StereoPoint2.h:131
Vector localCoordinates(const StereoPoint2 &t2) const
Definition: StereoPoint2.h:134
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
EIGEN_DEVICE_FUNC const Scalar & q
BinarySumExpression< T > operator-(const Expression< T > &e1, const Expression< T > &e2)
Construct an expression that subtracts one expression from another.
Definition: Expression.h:279
static Vector Logmap(const StereoPoint2 &p)
Definition: StereoPoint2.h:136
const G & b
Definition: Group.h:83
traits
Definition: chartTesting.h:28
StereoPoint2 operator-() const
inverse
Definition: StereoPoint2.h:79
Vector3 vector() const
Definition: StereoPoint2.h:115
ofstream os("timeSchurFactors.csv")
bool equals(const StereoPoint2 &q, double tol=1e-9) const
Definition: StereoPoint2.h:64
BinarySumExpression< T > operator+(const Expression< T > &e1, const Expression< T > &e2)
Definition: Expression.h:273
Expression< T > compose(const Expression< T > &t1, const Expression< T > &t2)
float * p
static Point3 p2
const G double tol
Definition: Group.h:83
#define abs(x)
Definition: datatypes.h:17
2D Point
StereoPoint2(const Vector3 &v)
construct from 3D vector
Definition: StereoPoint2.h:53
Expression< T > between(const Expression< T > &t1, const Expression< T > &t2)


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:44:50