g2o
edge_se3_plane_calib.cpp
Go to the documentation of this file.
1 // g2o - General Graph Optimization
2 // Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard
3 // All rights reserved.
4 //
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are
7 // met:
8 //
9 // * Redistributions of source code must retain the above copyright notice,
10 // this list of conditions and the following disclaimer.
11 // * Redistributions in binary form must reproduce the above copyright
12 // notice, this list of conditions and the following disclaimer in the
13 // documentation and/or other materials provided with the distribution.
14 //
15 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS
16 // IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED
17 // TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A
18 // PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
19 // HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
20 // SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED
21 // TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
22 // PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
23 // LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
24 // NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 
27 #include <iostream>
28 #include "edge_se3_plane_calib.h"
29 
31 
32 namespace g2o
33 {
34  using namespace std;
35  using namespace Eigen;
36 
39  {
40  resize(3);
41  color << 0.1, 0.1, 0.1;
42  }
43 
44  bool EdgeSE3PlaneSensorCalib::read(std::istream& is)
45  {
46  Vector4D v;
47  is >> v(0) >> v(1) >> v(2) >> v(3);
49  is >> color(0) >> color(1) >> color(2);
50  for (int i = 0; i < information().rows(); ++i)
51  for (int j = i; j < information().cols(); ++j) {
52  is >> information()(i, j);
53  if (i != j)
54  information()(j, i) = information()(i, j);
55  }
56  return true;
57  }
58 
59  bool EdgeSE3PlaneSensorCalib::write(std::ostream& os) const
60  {
62  os << v(0) << " " << v(1) << " " << v(2) << " " << v(3) << " ";
63  os << color(0) << " " << color(1) << " " << color(2) << " ";
64  for (int i = 0; i < information().rows(); ++i)
65  for (int j = i; j < information().cols(); ++j)
66  os << " " << information()(i, j);
67  return os.good();
68  }
69 
70 
71 #ifdef G2O_HAVE_OPENGL
72 
73  EdgeSE3PlaneSensorCalibDrawAction::EdgeSE3PlaneSensorCalibDrawAction(): DrawAction(typeid(EdgeSE3PlaneSensorCalib).name()){
74  }
75 
76  bool EdgeSE3PlaneSensorCalibDrawAction::refreshPropertyPtrs(HyperGraphElementAction::Parameters* params_){
77  if (!DrawAction::refreshPropertyPtrs(params_))
78  return false;
79  if (_previousParams){
80  _planeWidth = _previousParams->makeProperty<FloatProperty>(_typeName + "::PLANE_WIDTH", 3.0f);
81  _planeHeight = _previousParams->makeProperty<FloatProperty>(_typeName + "::PLANE_HEIGHT", 3.0f);
82  } else {
83  _planeWidth = 0;
84  _planeHeight = 0;
85  }
86  return true;
87  }
88 
89  HyperGraphElementAction* EdgeSE3PlaneSensorCalibDrawAction::operator()(HyperGraph::HyperGraphElement* element,
91  {
92  if (typeid(*element).name()!=_typeName)
93  return 0;
94 
95  refreshPropertyPtrs(params_);
96  if (! _previousParams)
97  return this;
98 
99  if (_show && !_show->value())
100  return this;
101 
102  EdgeSE3PlaneSensorCalib* that = dynamic_cast<EdgeSE3PlaneSensorCalib*>(element);
103 
104  if (! that)
105  return this;
106 
107  const VertexSE3* robot = dynamic_cast<const VertexSE3*>(that->vertex(0));
108  const VertexSE3* sensor = dynamic_cast<const VertexSE3*>(that->vertex(2));
109 
110  if (! robot|| ! sensor)
111  return 0;
112 
113  double d=that->measurement().distance();
114  double azimuth=Plane3D::azimuth(that->measurement().normal());
115  double elevation=Plane3D::elevation(that->measurement().normal());
116 
117  glColor3f(float(that->color(0)), float(that->color(1)), float(that->color(2)));
118  glPushMatrix();
119  Isometry3D robotAndSensor = robot->estimate() * sensor->estimate();
120  glMultMatrixd(robotAndSensor.matrix().data());
121 
122  glRotatef(float(RAD2DEG(azimuth)), 0.f, 0.f, 1.f);
123  glRotatef(float(RAD2DEG(elevation)), 0.f, -1.f, 0.f);
124  glTranslatef(float(d), 0.f, 0.f);
125 
126  float planeWidth = 0.5f;
127  float planeHeight = 0.5f;
128  if (0) {
129  planeWidth = _planeWidth->value();
130  planeHeight = _planeHeight->value();
131  }
132  if (_planeWidth && _planeHeight){
133  glBegin(GL_QUADS);
134  glNormal3f(-1,0,0);
135  glVertex3f(0,-planeWidth, -planeHeight);
136  glVertex3f(0, planeWidth, -planeHeight);
137  glVertex3f(0, planeWidth, planeHeight);
138  glVertex3f(0,-planeWidth, planeHeight);
139  glEnd();
140  }
141 
142  glPopMatrix();
143 
144  return this;
145  }
146 #endif
147 
148 } // end namespace
const Vertex * vertex(size_t i) const
Definition: hyper_graph.h:186
virtual bool write(std::ostream &os) const
write the vertex to a stream
static double elevation(const Eigen::Vector3d &v)
Definition: plane3d.h:68
virtual bool read(std::istream &is)
read the vertex from a stream, i.e., the internal state of the vertex
Abstract action that operates on a graph entity.
Eigen::Matrix< double, 4, 1, Eigen::ColMajor > Vector4D
Definition: eigen_types.h:47
static double azimuth(const Eigen::Vector3d &v)
Definition: plane3d.h:64
plane measurement that also calibrates an offset for the sensor
Eigen::Transform< double, 3, Eigen::Isometry, Eigen::ColMajor > Isometry3D
Definition: eigen_types.h:66
base class to represent an edge connecting an arbitrary number of nodes
Eigen::Vector3d normal() const
Definition: plane3d.h:76
void setMeasurement(const Plane3D &m)
virtual void resize(size_t size)
EIGEN_STRONG_INLINE const InformationType & information() const
information matrix of the constraint
Definition: base_edge.h:67
const EstimateType & estimate() const
return the current estimate of the vertex
Definition: base_vertex.h:99
virtual bool refreshPropertyPtrs(HyperGraphElementAction::Parameters *params_)
3D pose Vertex, represented as an Isometry3D
Definition: vertex_se3.h:50
#define RAD2DEG(x)
Definition: macros.h:35
Eigen::Vector4d toVector() const
Definition: plane3d.h:53
double distance() const
Definition: plane3d.h:72
EIGEN_STRONG_INLINE const Measurement & measurement() const
accessor functions for the measurement represented by the edge
Definition: base_edge.h:75