g2o
Typedefs | Functions
plane_test.cpp File Reference
#include <list>
#include <iostream>
#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

Definition at line 15 of file plane_test.cpp.

Function Documentation

int main ( )

Definition at line 33 of file plane_test.cpp.

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

33  {
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
Eigen::Vector3d ominus(const Plane3D &plane)
Definition: plane3d.h:102
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
Eigen::Vector3d normal() const
Definition: plane3d.h:76
ostream& operator<< ( ostream &  os,
const Plane3D p 
)

Definition at line 9 of file plane_test.cpp.

References g2o::Plane3D::toVector().

9  {
10  Eigen::Vector4d v=p.toVector();
11  os << "coeffs: " << v[0] << " " << v[1] << " " << v[2] << " " << v[3];
12  return os;
13 }
Eigen::Vector4d toVector() const
Definition: plane3d.h:53
ostream& operator<< ( ostream &  os,
const PlaneList l 
)

Definition at line 24 of file plane_test.cpp.

24  {
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 }
void transform ( PlaneList l,
const SE3Quat t 
)

Definition at line 17 of file plane_test.cpp.

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

17  {
18  for (PlaneList::iterator it=l.begin(); it!=l.end(); it++){
19  Plane3D *p = *it;
20  *p = t*(*p);
21  }
22 }