g2o
edge_se2.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.h"
28 
29 #ifdef G2O_HAVE_OPENGL
32 #endif
33 
34 namespace g2o {
35 
38  {
39  }
40 
41  bool EdgeSE2::read(std::istream& is)
42  {
43  Vector3D p;
44  is >> p[0] >> p[1] >> p[2];
45  setMeasurement(SE2(p));
47  for (int i = 0; i < 3; ++i)
48  for (int j = i; j < 3; ++j) {
49  is >> information()(i, j);
50  if (i != j)
51  information()(j, i) = information()(i, j);
52  }
53  return true;
54  }
55 
56  bool EdgeSE2::write(std::ostream& os) const
57  {
59  os << p.x() << " " << p.y() << " " << p.z();
60  for (int i = 0; i < 3; ++i)
61  for (int j = i; j < 3; ++j)
62  os << " " << information()(i, j);
63  return os.good();
64  }
65 
67  {
68  VertexSE2* fromEdge = static_cast<VertexSE2*>(_vertices[0]);
69  VertexSE2* toEdge = static_cast<VertexSE2*>(_vertices[1]);
70  if (from.count(fromEdge) > 0)
71  toEdge->setEstimate(fromEdge->estimate() * _measurement);
72  else
73  fromEdge->setEstimate(toEdge->estimate() * _inverseMeasurement);
74  }
75 
76 #ifndef NUMERIC_JACOBIAN_TWO_D_TYPES
78  {
79  const VertexSE2* vi = static_cast<const VertexSE2*>(_vertices[0]);
80  const VertexSE2* vj = static_cast<const VertexSE2*>(_vertices[1]);
81  double thetai = vi->estimate().rotation().angle();
82 
83  Vector2D dt = vj->estimate().translation() - vi->estimate().translation();
84  double si=sin(thetai), ci=cos(thetai);
85 
86  _jacobianOplusXi(0, 0) = -ci; _jacobianOplusXi(0, 1) = -si; _jacobianOplusXi(0, 2) = -si*dt.x()+ci*dt.y();
87  _jacobianOplusXi(1, 0) = si; _jacobianOplusXi(1, 1) = -ci; _jacobianOplusXi(1, 2) = -ci*dt.x()-si*dt.y();
88  _jacobianOplusXi(2, 0) = 0; _jacobianOplusXi(2, 1) = 0; _jacobianOplusXi(2, 2) = -1;
89 
90  _jacobianOplusXj(0, 0) = ci; _jacobianOplusXj(0, 1)= si; _jacobianOplusXj(0, 2)= 0;
91  _jacobianOplusXj(1, 0) =-si; _jacobianOplusXj(1, 1)= ci; _jacobianOplusXj(1, 2)= 0;
92  _jacobianOplusXj(2, 0) = 0; _jacobianOplusXj(2, 1)= 0; _jacobianOplusXj(2, 2)= 1;
93 
94  const SE2& rmean = _inverseMeasurement;
95  Matrix3D z = Matrix3D::Zero();
96  z.block<2, 2>(0, 0) = rmean.rotation().toRotationMatrix();
97  z(2, 2) = 1.;
100  }
101 #endif
102 
104 
106  if (typeid(*element).name()!=_typeName)
107  return 0;
108  WriteGnuplotAction::Parameters* params=static_cast<WriteGnuplotAction::Parameters*>(params_);
109  if (!params->os){
110  std::cerr << __PRETTY_FUNCTION__ << ": warning, on valid os specified" << std::endl;
111  return 0;
112  }
113 
114  EdgeSE2* e = static_cast<EdgeSE2*>(element);
115  VertexSE2* fromEdge = static_cast<VertexSE2*>(e->vertex(0));
116  VertexSE2* toEdge = static_cast<VertexSE2*>(e->vertex(1));
117  *(params->os) << fromEdge->estimate().translation().x() << " " << fromEdge->estimate().translation().y()
118  << " " << fromEdge->estimate().rotation().angle() << std::endl;
119  *(params->os) << toEdge->estimate().translation().x() << " " << toEdge->estimate().translation().y()
120  << " " << toEdge->estimate().rotation().angle() << std::endl;
121  *(params->os) << std::endl;
122  return this;
123  }
124 
125 #ifdef G2O_HAVE_OPENGL
126  EdgeSE2DrawAction::EdgeSE2DrawAction(): DrawAction(typeid(EdgeSE2).name()){}
127 
128  bool EdgeSE2DrawAction::refreshPropertyPtrs(HyperGraphElementAction::Parameters* params_){
129  if (!DrawAction::refreshPropertyPtrs(params_))
130  return false;
131  if (_previousParams){
132  _triangleX = _previousParams->makeProperty<FloatProperty>(_typeName + "::GHOST_TRIANGLE_X", .2f);
133  _triangleY = _previousParams->makeProperty<FloatProperty>(_typeName + "::GHOST_TRIANGLE_Y", .05f);
134  } else {
135  _triangleX = 0;
136  _triangleY = 0;
137  }
138  return true;
139  }
140 
141  HyperGraphElementAction* EdgeSE2DrawAction::operator()(HyperGraph::HyperGraphElement* element,
143  if (typeid(*element).name()!=_typeName)
144  return 0;
145 
146  refreshPropertyPtrs(params_);
147  if (! _previousParams)
148  return this;
149 
150  if (_show && !_show->value())
151  return this;
152 
153  EdgeSE2* e = static_cast<EdgeSE2*>(element);
154  VertexSE2* from = static_cast<VertexSE2*>(e->vertex(0));
155  VertexSE2* to = static_cast<VertexSE2*>(e->vertex(1));
156  if (! from && ! to)
157  return this;
158  SE2 fromTransform;
159  SE2 toTransform;
160  glPushAttrib(GL_ENABLE_BIT | GL_LIGHTING | GL_COLOR);
161  glDisable(GL_LIGHTING);
162  if (! from) {
163  glColor3f(POSE_EDGE_GHOST_COLOR);
164  toTransform = to->estimate();
165  fromTransform = to->estimate()*e->measurement().inverse();
166  // DRAW THE FROM EDGE AS AN ARROW
167  glPushMatrix();
168  glTranslatef((float)fromTransform.translation().x(), (float)fromTransform.translation().y(),0.f);
169  glRotatef((float)RAD2DEG(fromTransform.rotation().angle()),0.f,0.f,1.f);
170  opengl::drawArrow2D((float)_triangleX->value(), (float)_triangleY->value(), (float)_triangleX->value()*.3f);
171  glPopMatrix();
172  } else if (! to){
173  glColor3f(POSE_EDGE_GHOST_COLOR);
174  fromTransform = from->estimate();
175  toTransform = from->estimate()*e->measurement();
176  // DRAW THE TO EDGE AS AN ARROW
177  glPushMatrix();
178  glTranslatef(toTransform.translation().x(),toTransform.translation().y(),0.f);
179  glRotatef((float)RAD2DEG(toTransform.rotation().angle()),0.f,0.f,1.f);
180  opengl::drawArrow2D((float)_triangleX->value(), (float)_triangleY->value(), (float)_triangleX->value()*.3f);
181  glPopMatrix();
182  } else {
183  glColor3f(POSE_EDGE_COLOR);
184  fromTransform = from->estimate();
185  toTransform = to->estimate();
186  }
187  glBegin(GL_LINES);
188  glVertex3f((float)fromTransform.translation().x(),(float)fromTransform.translation().y(),0.f);
189  glVertex3f((float)toTransform.translation().x(),(float)toTransform.translation().y(),0.f);
190  glEnd();
191  glPopAttrib();
192  return this;
193  }
194 #endif
195 
196 } // end namespace
Eigen::Matrix< double, 2, 1, Eigen::ColMajor > Vector2D
Definition: eigen_types.h:45
const Vertex * vertex(size_t i) const
Definition: hyper_graph.h:186
#define __PRETTY_FUNCTION__
Definition: macros.h:89
#define POSE_EDGE_COLOR
virtual void setMeasurement(const SE2 &m)
Definition: edge_se2.h:56
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
2D edge between two Vertex2
Definition: edge_se2.h:40
Abstract action that operates on a graph entity.
Measurement _measurement
Definition: base_edge.h:87
std::set< Vertex * > VertexSet
Definition: hyper_graph.h:136
represent SE2
Definition: se2.h:40
2D pose Vertex, (x,y,theta)
Definition: vertex_se2.h:41
const std::string & name() const
returns the name of an action, e.g "draw"
void drawArrow2D(float len, float head_width, float head_len)
virtual void initialEstimate(const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *to)
Definition: edge_se2.cpp:66
const Eigen::Rotation2Dd & rotation() const
rotational component
Definition: se2.h:58
SE2 _inverseMeasurement
Definition: edge_se2.h:92
virtual HyperGraphElementAction * operator()(HyperGraph::HyperGraphElement *element, HyperGraphElementAction::Parameters *params_)
redefine this to do the action stuff. If successful, the action returns a pointer to itself ...
Definition: edge_se2.cpp:105
EIGEN_MAKE_ALIGNED_OPERATOR_NEW EdgeSE2()
Definition: edge_se2.cpp:36
Eigen::Matrix< double, 3, 3, Eigen::ColMajor > Matrix3D
Definition: eigen_types.h:61
#define POSE_EDGE_GHOST_COLOR
virtual bool read(std::istream &is)
read the vertex from a stream, i.e., the internal state of the vertex
Definition: edge_se2.cpp:41
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.
EIGEN_STRONG_INLINE const InformationType & information() const
information matrix of the constraint
Definition: base_edge.h:67
virtual bool write(std::ostream &os) const
write the vertex to a stream
Definition: edge_se2.cpp:56
const EstimateType & estimate() const
return the current estimate of the vertex
Definition: base_vertex.h:99
virtual bool refreshPropertyPtrs(HyperGraphElementAction::Parameters *params_)
SE2 inverse() const
invert :-)
Definition: se2.h:82
const Vector2D & translation() const
translational component
Definition: se2.h:54
#define RAD2DEG(x)
Definition: macros.h:35
EIGEN_STRONG_INLINE const Measurement & measurement() const
accessor functions for the measurement represented by the edge
Definition: base_edge.h:75
virtual void linearizeOplus()
Definition: edge_se2.cpp:77
VertexContainer _vertices
Definition: hyper_graph.h:202