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 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
24 #include <boost/serialization/nvp.hpp>
25 #endif
26 
27 namespace gtsam {
28 
34 class GTSAM_EXPORT StereoPoint2 {
35 private:
36 
37  double uL_, uR_, v_;
38 
39 public:
40  inline constexpr static auto dimension = 3;
43 
46  uL_(0), uR_(0), v_(0) {
47  }
48 
52  StereoPoint2(double uL, double uR, double v) :
53  uL_(uL), uR_(uR), v_(v) {
54  }
55 
57  explicit StereoPoint2(const Vector3& v) :
58  uL_(v(0)), uR_(v(1)), v_(v(2)) {}
59 
63 
65  void print(const std::string& s = "") const;
66 
68  bool equals(const StereoPoint2& q, double tol = 1e-9) const {
69  return (std::abs(uL_ - q.uL_) < tol && std::abs(uR_ - q.uR_) < tol
70  && std::abs(v_ - q.v_) < tol);
71  }
72 
76 
78  inline static StereoPoint2 Identity() {
79  return StereoPoint2();
80  }
81 
84  return StereoPoint2(-uL_, -uR_, -v_);
85  }
86 
88  inline StereoPoint2 operator +(const Vector3& v) const {
89  return StereoPoint2(uL_ + v[0], uR_ + v[1], v_ + v[2]);
90  }
91 
93  inline StereoPoint2 operator +(const StereoPoint2& b) const {
94  return StereoPoint2(uL_ + b.uL_, uR_ + b.uR_, v_ + b.v_);
95  }
96 
98  inline StereoPoint2 operator -(const StereoPoint2& b) const {
99  return StereoPoint2(uL_ - b.uL_, uR_ - b.uR_, v_ - b.v_);
100  }
101 
105 
107  inline bool operator ==(const StereoPoint2& q) const {return uL_== q.uL_ && uR_==q.uR_ && v_ == q.v_;}
108 
110  inline double uL() const {return uL_;}
111 
113  inline double uR() const {return uR_;}
114 
116  inline double v() const {return v_;}
117 
119  Vector3 vector() const {
120  return Vector3(uL_, uR_, v_);
121  }
122 
124  Point2 point2() const {
125  return Point2(uL_, v_);
126  }
127 
129  Point2 right() const {
130  return Point2(uR_, v_);
131  }
132 
135  inline StereoPoint2 inverse() const { return StereoPoint2()- (*this);}
136  inline StereoPoint2 compose(const StereoPoint2& p1) const { return *this + p1;}
137  inline StereoPoint2 between(const StereoPoint2& p2) const { return p2 - *this; }
138  inline Vector localCoordinates(const StereoPoint2& t2) const { return Logmap(between(t2)); }
139  inline StereoPoint2 retract(const Vector& v) const { return compose(Expmap(v)); }
140  static inline Vector Logmap(const StereoPoint2& p) { return p.vector(); }
141  static inline StereoPoint2 Expmap(const Vector& d) { return StereoPoint2(d(0), d(1), d(2)); }
143 
145  GTSAM_EXPORT friend std::ostream &operator<<(std::ostream &os, const StereoPoint2& p);
146 
147 private:
148 
152 
153 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
154 
155  friend class boost::serialization::access;
156  template<class ARCHIVE>
157  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
158  ar & BOOST_SERIALIZATION_NVP(uL_);
159  ar & BOOST_SERIALIZATION_NVP(uR_);
160  ar & BOOST_SERIALIZATION_NVP(v_);
161  }
162 #endif
163 
165 
166 };
167 
168 typedef std::vector<StereoPoint2> StereoPoint2Vector;
169 
170 template<>
171 struct traits<StereoPoint2> : public internal::VectorSpace<StereoPoint2> {};
172 
173 template<>
174 struct traits<const StereoPoint2> : public internal::VectorSpace<StereoPoint2> {};
175 }
gtsam::StereoPoint2::right
Point2 right() const
Definition: StereoPoint2.h:129
gtsam::StereoPoint2::uL
double uL() const
get uL
Definition: StereoPoint2.h:110
gtsam::StereoPoint2::Logmap
static Vector Logmap(const StereoPoint2 &p)
Definition: StereoPoint2.h:140
gtsam::StereoPoint2::vector
Vector3 vector() const
Definition: StereoPoint2.h:119
gtsam::StereoPoint2::StereoPoint2
StereoPoint2(double uL, double uR, double v)
Definition: StereoPoint2.h:52
gtsam::between
Expression< T > between(const Expression< T > &t1, const Expression< T > &t2)
Definition: nonlinear/expressions.h:17
s
RealScalar s
Definition: level1_cplx_impl.h:126
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
d
static const double d[K][N]
Definition: igam.h:11
gtsam::operator<<
std::ostream & operator<<(std::ostream &os, const Dih6 &m)
Definition: testGroup.cpp:109
gtsam::StereoPoint2::Identity
static StereoPoint2 Identity()
identity
Definition: StereoPoint2.h:78
gtsam::operator-
Errors operator-(const Errors &a, const Errors &b)
Subtraction.
Definition: Errors.cpp:74
gtsam::StereoPoint2::operator-
StereoPoint2 operator-() const
inverse
Definition: StereoPoint2.h:83
gtsam::internal::VectorSpace
VectorSpace provides both Testable and VectorSpaceTraits.
Definition: VectorSpace.h:207
gtsam::StereoPoint2Vector
std::vector< StereoPoint2 > StereoPoint2Vector
Definition: StereoPoint2.h:168
gtsam::StereoPoint2::point2
Point2 point2() const
Definition: StereoPoint2.h:124
gtsam::StereoPoint2::compose
StereoPoint2 compose(const StereoPoint2 &p1) const
Definition: StereoPoint2.h:136
gtsam::StereoPoint2::v
double v() const
get v
Definition: StereoPoint2.h:116
gtsam::Vector3
Eigen::Vector3d Vector3
Definition: Vector.h:44
gtsam::operator==
bool operator==(const Matrix &A, const Matrix &B)
Definition: base/Matrix.h:99
os
ofstream os("timeSchurFactors.csv")
gtsam::StereoPoint2::equals
bool equals(const StereoPoint2 &q, double tol=1e-9) const
Definition: StereoPoint2.h:68
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:39
gtsam::StereoPoint2::v_
double v_
Definition: StereoPoint2.h:37
Point2.h
2D Point
gtsam::StereoPoint2::Expmap
static StereoPoint2 Expmap(const Vector &d)
Definition: StereoPoint2.h:141
gtsam::compose
Expression< T > compose(const Expression< T > &t1, const Expression< T > &t2)
Definition: nonlinear/expressions.h:23
simple::p2
static Point3 p2
Definition: testInitializePose3.cpp:51
Expmap
Pose2_ Expmap(const Vector3_ &xi)
Definition: InverseKinematicsExampleExpressions.cpp:47
gtsam::print
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:156
Eigen::numext::q
EIGEN_DEVICE_FUNC const Scalar & q
Definition: SpecialFunctionsImpl.h:1984
gtsam::Point2
Vector2 Point2
Definition: Point2.h:32
gtsam::StereoPoint2::retract
StereoPoint2 retract(const Vector &v) const
Definition: StereoPoint2.h:139
p1
Vector3f p1
Definition: MatrixBase_all.cpp:2
gtsam::operator+
HybridGaussianProductFactor operator+(const HybridGaussianProductFactor &a, const HybridGaussianProductFactor &b)
Definition: HybridGaussianProductFactor.cpp:39
gtsam::b
const G & b
Definition: Group.h:79
gtsam::StereoPoint2::StereoPoint2
StereoPoint2(const Vector3 &v)
construct from 3D vector
Definition: StereoPoint2.h:57
gtsam
traits
Definition: SFMdata.h:40
gtsam::traits
Definition: Group.h:36
gtsam::StereoPoint2
Definition: StereoPoint2.h:34
p
float * p
Definition: Tutorial_Map_using.cpp:9
v
Array< int, Dynamic, 1 > v
Definition: Array_initializer_list_vector_cxx11.cpp:1
gtsam::StereoPoint2::StereoPoint2
StereoPoint2()
Definition: StereoPoint2.h:45
gtsam::StereoPoint2::uR
double uR() const
get uR
Definition: StereoPoint2.h:113
gtsam::tol
const G double tol
Definition: Group.h:79
abs
#define abs(x)
Definition: datatypes.h:17
gtsam::StereoPoint2::localCoordinates
Vector localCoordinates(const StereoPoint2 &t2) const
Definition: StereoPoint2.h:138
gtsam::StereoPoint2::between
StereoPoint2 between(const StereoPoint2 &p2) const
Definition: StereoPoint2.h:137
VectorSpace.h
gtsam::StereoPoint2::inverse
StereoPoint2 inverse() const
Definition: StereoPoint2.h:135


gtsam
Author(s):
autogenerated on Sun Dec 22 2024 04:14:03