g2o
edge_se2_sensor_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 "edge_se2_sensor_calib.h"
28 #ifdef G2O_HAVE_OPENGL
30 #endif
31 namespace g2o {
32 
34  BaseMultiEdge<3, SE2>()
35  {
36  resize(3);
37  }
38 
40  {
41  (void) to;
42  VertexSE2* vi = static_cast<VertexSE2*>(_vertices[0]);
43  VertexSE2* vj = static_cast<VertexSE2*>(_vertices[1]);
44  VertexSE2* l = static_cast<VertexSE2*>(_vertices[2]);
45  if (from.count(l) == 0)
46  return;
47  if (from.count(vi) == 1) {
48  vj->setEstimate(vi->estimate() * l->estimate() * measurement() * l->estimate().inverse());
49  } else {
50  vi->setEstimate(vj->estimate() * l->estimate() * _inverseMeasurement * l->estimate().inverse());
51  }
52  }
53 
54  bool EdgeSE2SensorCalib::read(std::istream& is)
55  {
56  Vector3D p;
57  is >> p(0) >> p(1) >> p(2);
60  for (int i = 0; i < information().rows(); ++i)
61  for (int j = i; j < information().cols(); ++j) {
62  is >> information()(i, j);
63  if (i != j)
64  information()(j, i) = information()(i, j);
65  }
66  return true;
67  }
68 
69  bool EdgeSE2SensorCalib::write(std::ostream& os) const
70  {
72  os << p(0) << " " << p(1) << " " << p(2);
73  for (int i = 0; i < information().rows(); ++i)
74  for (int j = i; j < information().cols(); ++j)
75  os << " " << information()(i, j);
76  return os.good();
77  }
78 
79 #ifdef G2O_HAVE_OPENGL
80  EdgeSE2SensorCalibDrawAction::EdgeSE2SensorCalibDrawAction() :
81  DrawAction(typeid(EdgeSE2SensorCalib).name())
82  {
83  }
84 
85  HyperGraphElementAction* EdgeSE2SensorCalibDrawAction::operator()(HyperGraph::HyperGraphElement* element, HyperGraphElementAction::Parameters* )
86  {
87  if (typeid(*element).name()!=_typeName)
88  return 0;
89  EdgeSE2SensorCalib* e = static_cast<EdgeSE2SensorCalib*>(element);
90  VertexSE2* fromEdge = static_cast<VertexSE2*>(e->vertex(0));
91  VertexSE2* toEdge = static_cast<VertexSE2*>(e->vertex(1));
92  glColor3f(0.5,0.5,1.0);
93  glPushAttrib(GL_ENABLE_BIT);
94  glDisable(GL_LIGHTING);
95  glBegin(GL_LINES);
96  glVertex3f((float)fromEdge->estimate().translation().x(),(float)fromEdge->estimate().translation().y(),0.f);
97  glVertex3f((float)toEdge->estimate().translation().x(),(float)toEdge->estimate().translation().y(),0.f);
98  glEnd();
99  glPopAttrib();
100  return this;
101  }
102 #endif
103 
104 } // end namespace
const Vertex * vertex(size_t i) const
Definition: hyper_graph.h:186
Vector3D toVector() const
convert to a 3D vector (x, y, theta)
Definition: se2.h:108
Eigen::Matrix< double, 3, 1, Eigen::ColMajor > Vector3D
Definition: eigen_types.h:46
Abstract action that operates on a graph entity.
scanmatch measurement that also calibrates an offset for the laser
Measurement _measurement
Definition: base_edge.h:87
std::set< Vertex * > VertexSet
Definition: hyper_graph.h:136
virtual bool write(std::ostream &os) const
write the vertex to a stream
represent SE2
Definition: se2.h:40
2D pose Vertex, (x,y,theta)
Definition: vertex_se2.h:41
virtual void initialEstimate(const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *to)
void fromVector(const Vector3D &v)
assign from a 3D vector (x, y, theta)
Definition: se2.h:103
base class to represent an edge connecting an arbitrary number of nodes
void setEstimate(const EstimateType &et)
set the estimate for the vertex also calls updateCache()
Definition: base_vertex.h:101
A general case Vertex for optimization.
virtual void resize(size_t size)
EIGEN_STRONG_INLINE const InformationType & information() const
information matrix of the constraint
Definition: base_edge.h:67
virtual bool read(std::istream &is)
read the vertex from a stream, i.e., the internal state of the vertex
const EstimateType & estimate() const
return the current estimate of the vertex
Definition: base_vertex.h:99
SE2 inverse() const
invert :-)
Definition: se2.h:82
const Vector2D & translation() const
translational component
Definition: se2.h:54
EIGEN_STRONG_INLINE const Measurement & measurement() const
accessor functions for the measurement represented by the edge
Definition: base_edge.h:75
VertexContainer _vertices
Definition: hyper_graph.h:202