g2o
Loading...
Searching...
No Matches
Typedefs | Functions
plane_test.cpp File Reference
#include <iostream>
#include <list>
#include "plane3d.h"
Include dependency graph for plane_test.cpp:

Go to the source code of this file.

Typedefs

typedef std::list< Plane3D * > PlaneList
 

Functions

ostream & operator<< (ostream &os, const Plane3D &p)
 
void transform (PlaneList &l, const SE3Quat &t)
 
ostream & operator<< (ostream &os, const PlaneList &l)
 
int main ()
 

Typedef Documentation

◆ PlaneList

typedef std::list<Plane3D*> PlaneList

Definition at line 42 of file plane_test.cpp.

Function Documentation

◆ main()

int main ( )

Definition at line 59 of file plane_test.cpp.

59 {
60 Plane3D p;
61 cerr << "p0 " << p << endl;
62 Eigen::Vector4d v;
63 v << 0.5, 0.2, 0.1, 10;
64 Plane3D p1;
65 p1.fromVector(v);
66 cerr << "p1 " << p1 << endl;
67 Plane3D p2 = p1;
68 cerr << "p2 " << p2 << endl;
69
70 cerr << "azimuth " << Plane3D::azimuth(p1.normal()) << endl;
71 cerr << "elevation " << Plane3D::elevation(p1.normal()) << endl;
72 Vector3d mv = p2.ominus(p1);
73 cerr << "p ominus p " << mv[0] << " " << mv[1] << " " << mv[2] << endl;
74
75 p1.fromVector(Eigen::Vector4d(2, 2, 100, 10));
76 cerr << "p1 " << p1 << endl;
77 cerr << "azimuth " << Plane3D::azimuth(p1.normal()) << endl;
78 cerr << "elevation " << Plane3D::elevation(p1.normal()) << endl;
79 p2.fromVector(Eigen::Vector4d(-2, -2, 100, 100));
80 cerr << "p2 " << p2 << endl;
81 cerr << "azimuth " << Plane3D::azimuth(p2.normal()) << endl;
82 cerr << "elevation " << Plane3D::elevation(p2.normal()) << endl;
83
84 mv = p2.ominus(p1);
85 cerr << "p ominus p " << mv[0] << " " << mv[1] << " " << mv[2] << endl;
86
87 Plane3D p3 = p1;
88 cerr << "p3 " << p3 << endl;
89 p3.oplus(mv);
90 cerr << "p3.oplus(mv) " << p3 << endl;
91
92 PlaneList l;
93 Plane3D* pp = new Plane3D();
94 Eigen::Vector4d coeffs;
95 coeffs << 1., 0., 0., 1.;
96 pp->fromVector(coeffs);
97 l.push_back(pp);
98
99 pp = new Plane3D();
100 coeffs << 0., 1., 0., 1.;
101 pp->fromVector(coeffs);
102 l.push_back(pp);
103
104 pp = new Plane3D();
105 coeffs << 0., 0., 1., 1.;
106 pp->fromVector(coeffs);
107 l.push_back(pp);
108
109 cerr << l << endl;
110
111 AngleAxisd r(AngleAxisd(0.0, Vector3d::UnitZ()) *
112 AngleAxisd(0., Vector3d::UnitY()) *
113 AngleAxisd(0., Vector3d::UnitX()));
114
115 SE3Quat t(r.toRotationMatrix(), Vector3d(0.9, 0, 0));
116 cerr << t << endl;
117 transform(l, t);
118 cerr << l << endl;
119
120 return 0;
121}
Vector3 ominus(const Plane3D &plane)
Definition plane3d.h:90
void fromVector(const Vector4 &coeffs_)
Definition plane3d.h:52
Vector3 normal() const
Definition plane3d.h:65
static double elevation(const Vector3 &v)
Definition plane3d.h:59
void oplus(const Vector3 &v)
Definition plane3d.h:75
static double azimuth(const Vector3 &v)
Definition plane3d.h:57
std::list< Plane3D * > PlaneList
void transform(PlaneList &l, const SE3Quat &t)

References g2o::Plane3D::azimuth(), g2o::Plane3D::elevation(), g2o::Plane3D::fromVector(), g2o::Plane3D::normal(), g2o::Plane3D::ominus(), g2o::Plane3D::oplus(), and transform().

◆ operator<<() [1/2]

ostream & operator<< ( ostream &  os,
const Plane3D p 
)

Definition at line 36 of file plane_test.cpp.

36 {
37 Eigen::Vector4d v = p.toVector();
38 os << "coeffs: " << v[0] << " " << v[1] << " " << v[2] << " " << v[3];
39 return os;
40}
Vector4 toVector() const
Definition plane3d.h:48

References g2o::Plane3D::toVector().

◆ operator<<() [2/2]

ostream & operator<< ( ostream &  os,
const PlaneList l 
)

Definition at line 51 of file plane_test.cpp.

51 {
52 for (PlaneList::const_iterator it = l.begin(); it != l.end(); ++it) {
53 const Plane3D* p = *it;
54 os << *p << endl;
55 }
56 return os;
57}

◆ transform()

void transform ( PlaneList l,
const SE3Quat t 
)

Definition at line 44 of file plane_test.cpp.

44 {
45 for (PlaneList::iterator it = l.begin(); it != l.end(); ++it) {
46 Plane3D* p = *it;
47 *p = t * (*p);
48 }
49}

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