g2o
plane_test.cpp
Go to the documentation of this file.
1 #include <list>
2 #include <iostream>
3 #include "plane3d.h"
4 
5 using namespace g2o;
6 using namespace std;
7 using namespace Eigen;
8 
9 ostream& operator << (ostream& os, const Plane3D& p){
10  Eigen::Vector4d v=p.toVector();
11  os << "coeffs: " << v[0] << " " << v[1] << " " << v[2] << " " << v[3];
12  return os;
13 }
14 
15 typedef std::list<Plane3D*> PlaneList;
16 
17 void transform(PlaneList& l, const SE3Quat& t){
18  for (PlaneList::iterator it=l.begin(); it!=l.end(); it++){
19  Plane3D *p = *it;
20  *p = t*(*p);
21  }
22 }
23 
24 ostream& operator << (ostream& os, const PlaneList& l){
25  for (PlaneList::const_iterator it=l.begin(); it!=l.end(); it++){
26  const Plane3D *p = *it;
27  os << *p << endl;
28  }
29  return os;
30 }
31 
32 
33 int main (/*int argc, char** argv*/){
34  Plane3D p;
35  cerr << "p0 " << p << endl;
36  Eigen::Vector4d v;
37  v << 0.5 , 0.2 , 0.1 , 10;
38  Plane3D p1;
39  p1.fromVector(v);
40  cerr << "p1 " << p1 << endl;
41  Plane3D p2 = p1;
42  cerr << "p2 " << p2 << endl;
43 
44  cerr << "azimuth " << Plane3D::azimuth(p1.normal()) << endl;
45  cerr << "elevation " << Plane3D::elevation(p1.normal()) << endl;
46  Vector3d mv = p2.ominus(p1);
47  cerr << "p ominus p " << mv[0] << " " << mv[1] << " " << mv[2] << endl;
48 
49  p1.fromVector(Eigen::Vector4d(2,2,100,10));
50  cerr << "p1 " << p1 << endl;
51  cerr << "azimuth " << Plane3D::azimuth(p1.normal()) << endl;
52  cerr << "elevation " << Plane3D::elevation(p1.normal()) << endl;
53  p2.fromVector(Eigen::Vector4d(-2,-2,100,100));
54  cerr << "p2 " << p2 << endl;
55  cerr << "azimuth " << Plane3D::azimuth(p2.normal()) << endl;
56  cerr << "elevation " << Plane3D::elevation(p2.normal()) << endl;
57 
58  mv = p2.ominus(p1);
59  cerr << "p ominus p " << mv[0] << " " << mv[1] << " " << mv[2] << endl;
60 
61  Plane3D p3=p1;
62  cerr << "p3 " << p3 << endl;
63  p3.oplus(mv);
64  cerr << "p3.oplus(mv) " << p3 << endl;
65 
66  PlaneList l;
67  Plane3D* pp = new Plane3D();
68  Eigen::Vector4d coeffs;
69  coeffs << 1., 0., 0., 1.;
70  pp->fromVector(coeffs);
71  l.push_back(pp);
72 
73  pp = new Plane3D();
74  coeffs << 0., 1., 0., 1.;
75  pp->fromVector(coeffs);
76  l.push_back(pp);
77 
78  pp = new Plane3D();
79  coeffs << 0., 0., 1., 1.;
80  pp->fromVector(coeffs);
81  l.push_back(pp);
82 
83  cerr << l << endl;
84 
85  AngleAxisd r(AngleAxisd(0.0, Vector3d::UnitZ())
86  * AngleAxisd(0., Vector3d::UnitY())
87  * AngleAxisd(0., Vector3d::UnitX()));
88 
89  SE3Quat t(r.toRotationMatrix(), Vector3d(0.9,0,0));
90  cerr << t << endl;
91  transform(l,t);
92  cerr << l << endl;
93 
94  return 0;
95 }
void oplus(const Eigen::Vector3d &v)
Definition: plane3d.h:87
static double elevation(const Eigen::Vector3d &v)
Definition: plane3d.h:68
Eigen::Vector3d ominus(const Plane3D &plane)
Definition: plane3d.h:102
static double azimuth(const Eigen::Vector3d &v)
Definition: plane3d.h:64
void transform(PlaneList &l, const SE3Quat &t)
Definition: plane_test.cpp:17
void fromVector(const Eigen::Vector4d &coeffs_)
Definition: plane3d.h:59
std::list< Plane3D * > PlaneList
Definition: plane_test.cpp:15
std::ostream & operator<<(std::ostream &os, const G2OBatchStatistics &st)
Definition: batch_stats.cpp:48
int main()
Definition: plane_test.cpp:33
Eigen::Vector3d normal() const
Definition: plane3d.h:76
Eigen::Vector4d toVector() const
Definition: plane3d.h:53