#include <plane3d.h>
Definition at line 38 of file plane3d.h.
◆ Plane3D() [1/2]
| g2o::Plane3D::Plane3D |
( |
| ) |
|
|
inline |
Definition at line 44 of file plane3d.h.
void fromVector(const Vector4 &coeffs_)
◆ Plane3D() [2/2]
| g2o::Plane3D::Plane3D |
( |
const Vector4 & |
v | ) |
|
|
inline |
◆ 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 |
◆ distance()
| double g2o::Plane3D::distance |
( |
| ) |
const |
|
inline |
◆ 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 {
55 }
static void normalize(Vector4 &coeffs)
Referenced by main(), and main().
◆ normal()
| Vector3 g2o::Plane3D::normal |
( |
| ) |
const |
|
inline |
◆ 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();
102 }
const Vector4 & coeffs() const
◆ ominus()
◆ oplus()
| void g2o::Plane3D::oplus |
( |
const Vector3 & |
v | ) |
|
|
inline |
Definition at line 75 of file plane3d.h.
75 {
76
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
88 }
Referenced by main(), and PlaneSensor::sense().
◆ rotation()
Definition at line 67 of file plane3d.h.
67 {
70 return (
AngleAxis(_azimuth, Vector3::UnitZ()) *
72 .toRotationMatrix();
73 }
Eigen::AngleAxis< double > AngleAxis
◆ toVector()
| Vector4 g2o::Plane3D::toVector |
( |
| ) |
const |
|
inline |
◆ operator*
Definition at line 107 of file plane3d.h.
107 {
111 v2.head<3>() = R * v.head<3>();
112 v2(3) = v(3) - t.translation().dot(v2.head<3>());
114};
◆ _coeffs
◆ EIGEN_MAKE_ALIGNED_OPERATOR_NEW
| g2o::Plane3D::EIGEN_MAKE_ALIGNED_OPERATOR_NEW |
The documentation for this class was generated from the following file:
- /build/reproducible-path/g2o-0~20230806/g2o/types/slam3d_addons/plane3d.h