g2o
Loading...
Searching...
No Matches
Public Member Functions | Static Public Member Functions | Public Attributes | Static Protected Member Functions | Protected Attributes | Friends | List of all members
g2o::Plane3D Class Reference

#include <plane3d.h>

Public Member Functions

 Plane3D ()
 
 Plane3D (const Vector4 &v)
 
Vector4 toVector () const
 
const Vector4coeffs () const
 
void fromVector (const Vector4 &coeffs_)
 
double distance () const
 
Vector3 normal () const
 
void oplus (const Vector3 &v)
 
Vector3 ominus (const Plane3D &plane)
 

Static Public Member Functions

static double azimuth (const Vector3 &v)
 
static double elevation (const Vector3 &v)
 
static Matrix3 rotation (const Vector3 &v)
 

Public Attributes

 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
 

Static Protected Member Functions

static void normalize (Vector4 &coeffs)
 

Protected Attributes

Vector4 _coeffs
 

Friends

Plane3D operator* (const Isometry3 &t, const Plane3D &plane)
 

Detailed Description

Definition at line 38 of file plane3d.h.

Constructor & Destructor Documentation

◆ Plane3D() [1/2]

g2o::Plane3D::Plane3D ( )
inline

Definition at line 44 of file plane3d.h.

44{ fromVector(Vector4(1., 0., 0., -1.)); }
void fromVector(const Vector4 &coeffs_)
Definition plane3d.h:52
VectorN< 4 > Vector4
Definition eigen_types.h:52

◆ Plane3D() [2/2]

g2o::Plane3D::Plane3D ( const Vector4 v)
inline

Definition at line 46 of file plane3d.h.

46{ fromVector(v); }

Member Function Documentation

◆ azimuth()

static double g2o::Plane3D::azimuth ( const Vector3 v)
inlinestatic

Definition at line 57 of file plane3d.h.

57{ return std::atan2(v(1), v(0)); }

Referenced by main().

◆ coeffs()

const Vector4 & g2o::Plane3D::coeffs ( ) const
inline

Definition at line 50 of file plane3d.h.

50{ return _coeffs; }
Vector4 _coeffs
Definition plane3d.h:104

◆ distance()

double g2o::Plane3D::distance ( ) const
inline

Definition at line 63 of file plane3d.h.

63{ return -_coeffs(3); }

Referenced by ominus().

◆ elevation()

static double g2o::Plane3D::elevation ( const Vector3 v)
inlinestatic

Definition at line 59 of file plane3d.h.

59 {
60 return std::atan2(v(2), v.head<2>().norm());
61 }

Referenced by main().

◆ fromVector()

void g2o::Plane3D::fromVector ( const Vector4 coeffs_)
inline

Definition at line 52 of file plane3d.h.

52 {
53 _coeffs = coeffs_;
55 }
static void normalize(Vector4 &coeffs)
Definition plane3d.h:99

Referenced by main(), and main().

◆ normal()

Vector3 g2o::Plane3D::normal ( ) const
inline

Definition at line 65 of file plane3d.h.

65{ return _coeffs.head<3>(); }

Referenced by main(), and ominus().

◆ normalize()

static void g2o::Plane3D::normalize ( Vector4 coeffs)
inlinestaticprotected

Definition at line 99 of file plane3d.h.

99 {
100 double n = coeffs.head<3>().norm();
101 coeffs = coeffs * (1. / n);
102 }
const Vector4 & coeffs() const
Definition plane3d.h:50

◆ ominus()

Vector3 g2o::Plane3D::ominus ( const Plane3D plane)
inline

Definition at line 90 of file plane3d.h.

90 {
91 // construct the rotation that would bring the plane normal in (1 0 0)
92 Matrix3 R = rotation(normal()).transpose();
93 Vector3 n = R * plane.normal();
94 double d = distance() - plane.distance();
95 return Vector3(azimuth(n), elevation(n), d);
96 }
Vector3 normal() const
Definition plane3d.h:65
static Matrix3 rotation(const Vector3 &v)
Definition plane3d.h:67
static double elevation(const Vector3 &v)
Definition plane3d.h:59
double distance() const
Definition plane3d.h:63
static double azimuth(const Vector3 &v)
Definition plane3d.h:57
VectorN< 3 > Vector3
Definition eigen_types.h:51
MatrixN< 3 > Matrix3
Definition eigen_types.h:72

References distance(), and normal().

Referenced by g2o::EdgeSE3PlaneSensorCalib::computeError(), and main().

◆ oplus()

void g2o::Plane3D::oplus ( const Vector3 v)
inline

Definition at line 75 of file plane3d.h.

75 {
76 // construct a normal from azimuth and elevation;
77 double _azimuth = v[0];
78 double _elevation = v[1];
79 double s = std::sin(_elevation), c = std::cos(_elevation);
80 Vector3 n(c * std::cos(_azimuth), c * std::sin(_azimuth), s);
81
82 // rotate the normal
83 Matrix3 R = rotation(normal());
84 double d = distance() + v[2];
85 _coeffs.head<3>() = R * n;
86 _coeffs(3) = -d;
88 }

Referenced by main(), and PlaneSensor::sense().

◆ rotation()

static Matrix3 g2o::Plane3D::rotation ( const Vector3 v)
inlinestatic

Definition at line 67 of file plane3d.h.

67 {
68 double _azimuth = azimuth(v);
69 double _elevation = elevation(v);
70 return (AngleAxis(_azimuth, Vector3::UnitZ()) *
71 AngleAxis(-_elevation, Vector3::UnitY()))
72 .toRotationMatrix();
73 }
Eigen::AngleAxis< double > AngleAxis
Definition eigen_types.h:82

◆ toVector()

Vector4 g2o::Plane3D::toVector ( ) const
inline

Friends And Related Symbol Documentation

◆ operator*

Plane3D operator* ( const Isometry3 t,
const Plane3D plane 
)
friend

Definition at line 107 of file plane3d.h.

107 {
108 Vector4 v = plane._coeffs;
109 Vector4 v2;
110 Matrix3 R = t.rotation();
111 v2.head<3>() = R * v.head<3>();
112 v2(3) = v(3) - t.translation().dot(v2.head<3>());
113 return Plane3D(v2);
114};

Member Data Documentation

◆ _coeffs

Vector4 g2o::Plane3D::_coeffs
protected

Definition at line 104 of file plane3d.h.

◆ EIGEN_MAKE_ALIGNED_OPERATOR_NEW

g2o::Plane3D::EIGEN_MAKE_ALIGNED_OPERATOR_NEW

Definition at line 40 of file plane3d.h.


The documentation for this class was generated from the following file: