OrientedPlane3.h
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * Atlanta, Georgia 30332-0415
4  * All Rights Reserved
5  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
12 /*
13  * @file OrientedPlane3.h
14  * @date Dec 19, 2013
15  * @author Alex Trevor
16  * @author Frank Dellaert
17  * @author Zhaoyang Lv
18  * @brief An infinite plane, represented by a normal direction and perpendicular distance
19  */
20 
21 #pragma once
22 
23 #include <gtsam/geometry/Unit3.h>
24 #include <gtsam/geometry/Pose3.h>
25 #include <string>
26 
27 namespace gtsam {
28 
36 class GTSAM_EXPORT OrientedPlane3 {
37 private:
39  double d_;
40 
41 public:
42  enum {
43  dimension = 3
44  };
45 
48 
51  n_(), d_(0.0) {
52  }
53 
55  OrientedPlane3(const Unit3& n, double d) :
56  n_(n), d_(d) {
57  }
58 
60  explicit OrientedPlane3(const Vector4& vec)
61  : n_(vec(0), vec(1), vec(2)), d_(vec(3)) {}
62 
64  OrientedPlane3(double a, double b, double c, double d) {
65  n_ = Unit3(a, b, c);
66  d_ = d;
67  }
68 
72 
74  void print(const std::string& s = std::string()) const;
75 
77  bool equals(const OrientedPlane3& s, double tol = 1e-9) const {
78  return (n_.equals(s.n_, tol) && (std::abs(d_ - s.d_) < tol));
79  }
80 
82 
89  OrientedPlane3 transform(const Pose3& xr,
90  OptionalJacobian<3, 3> Hp = boost::none,
91  OptionalJacobian<3, 6> Hr = boost::none) const;
92 
100  Vector3 errorVector(const OrientedPlane3& other,
101  OptionalJacobian<3, 3> H1 = boost::none,
102  OptionalJacobian<3, 3> H2 = boost::none) const;
103 
105  inline static size_t Dim() {
106  return 3;
107  }
108 
110  inline size_t dim() const {
111  return 3;
112  }
113 
115  OrientedPlane3 retract(const Vector3& v,
116  OptionalJacobian<3, 3> H = boost::none) const;
117 
119  Vector3 localCoordinates(const OrientedPlane3& s) const;
120 
122  inline Vector4 planeCoefficients() const {
123  Vector3 unit_vec = n_.unitVector();
124  return Vector4(unit_vec[0], unit_vec[1], unit_vec[2], d_);
125  }
126 
128  inline Unit3 normal() const {
129  return n_;
130  }
131 
133  inline double distance() const {
134  return d_;
135  }
136 
138 };
139 
140 template<> struct traits<OrientedPlane3> : public internal::Manifold<
141 OrientedPlane3> {
142 };
143 
144 template<> struct traits<const OrientedPlane3> : public internal::Manifold<
145 OrientedPlane3> {
146 };
147 
148 } // namespace gtsam
149 
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
Both ManifoldTraits and Testable.
Definition: Manifold.h:120
Eigen::Vector3d Vector3
Definition: Vector.h:43
OrientedPlane3(const Unit3 &n, double d)
Construct from a Unit3 and a distance.
ArrayXcf v
Definition: Cwise_arg.cpp:1
int n
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
GTSAM_EXPORT Vector3 unitVector(OptionalJacobian< 3, 2 > H=boost::none) const
Return unit-norm Vector.
Definition: Unit3.cpp:143
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size set set xzeroaxis lt lw set x2zeroaxis lt lw set yzeroaxis lt lw set y2zeroaxis lt lw set tics in set ticslevel set tics set mxtics default set mytics default set mx2tics default set my2tics default set xtics border mirror norotate autofreq set ytics border mirror norotate autofreq set ztics border nomirror norotate autofreq set nox2tics set noy2tics set timestamp bottom norotate set rrange[*:*] noreverse nowriteback set trange[*:*] noreverse nowriteback set urange[*:*] noreverse nowriteback set vrange[*:*] noreverse nowriteback set xlabel matrix size set x2label set timefmt d m y n H
OrientedPlane3()
Default constructor.
static size_t Dim()
Dimensionality of tangent space = 3 DOF.
Represents an infinite plane in 3D, which is composed of a planar normal and its perpendicular distan...
Array33i a
Represents a 3D point on a unit sphere.
Definition: Unit3.h:42
double d_
The perpendicular distance to this plane.
OrientedPlane3(double a, double b, double c, double d)
Construct from four numbers of plane coeffcients (a, b, c, d)
bool equals(const OrientedPlane3 &s, double tol=1e-9) const
The equals function with tolerance.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
EIGEN_DONT_INLINE void transform(const Transformation &t, Data &data)
Definition: geometry.cpp:25
double distance() const
Return the perpendicular distance to the origin.
size_t dim() const
Dimensionality of tangent space = 3 DOF.
const G & b
Definition: Group.h:83
traits
Definition: chartTesting.h:28
Vector4 planeCoefficients() const
Returns the plane coefficients.
const G double tol
Definition: Group.h:83
Unit3 n_
The direction of the planar normal.
#define abs(x)
Definition: datatypes.h:17
3D Pose
OrientedPlane3(const Vector4 &vec)
Construct from a vector of plane coefficients.
Unit3 normal() const
Return the normal.
bool equals(const Unit3 &s, double tol=1e-9) const
The equals function with tolerance.
Definition: Unit3.h:121


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:43:06