g2o
edge_se2_pointxy_bearing.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 
28 
29 #ifdef G2O_HAVE_OPENGL
32 #endif
33 
34 namespace g2o {
35 
37  {
38  }
39 
40 
42  {
43  assert(from.size() == 1 && from.count(_vertices[0]) == 1 && "Can not initialize VertexSE2 position by VertexPointXY");
44 
45  if (from.count(_vertices[0]) != 1)
46  return;
47  double r=2.;
48  const VertexSE2* v1 = static_cast<const VertexSE2*>(_vertices[0]);
49  VertexPointXY* l2 = static_cast<VertexPointXY*>(_vertices[1]);
50  SE2 t=v1->estimate();
51  t.setRotation(t.rotation()*Eigen::Rotation2Dd(_measurement));
52  Vector2D vr(r, 0.);
53  l2->setEstimate(t*vr);
54  }
55 
56  bool EdgeSE2PointXYBearing::read(std::istream& is)
57  {
58  is >> _measurement >> information()(0,0);
59  return true;
60  }
61 
62  bool EdgeSE2PointXYBearing::write(std::ostream& os) const
63  {
64  os << measurement() << " " << information()(0,0);
65  return os.good();
66  }
67 
68 
70 
73  if (typeid(*element).name()!=_typeName)
74  return 0;
76  if (!params->os){
77  std::cerr << __PRETTY_FUNCTION__ << ": warning, on valid os specified" << std::endl;
78  return 0;
79  }
80 
81  EdgeSE2PointXYBearing* e = static_cast<EdgeSE2PointXYBearing*>(element);
82  VertexSE2* fromEdge = static_cast<VertexSE2*>(e->vertex(0));
83  VertexPointXY* toEdge = static_cast<VertexPointXY*>(e->vertex(1));
84  *(params->os) << fromEdge->estimate().translation().x() << " " << fromEdge->estimate().translation().y()
85  << " " << fromEdge->estimate().rotation().angle() << std::endl;
86  *(params->os) << toEdge->estimate().x() << " " << toEdge->estimate().y() << std::endl;
87  *(params->os) << std::endl;
88  return this;
89  }
90 
91 #ifdef G2O_HAVE_OPENGL
92  EdgeSE2PointXYBearingDrawAction::EdgeSE2PointXYBearingDrawAction(): DrawAction(typeid(EdgeSE2PointXYBearing).name()){}
93 
94  HyperGraphElementAction* EdgeSE2PointXYBearingDrawAction::operator()(HyperGraph::HyperGraphElement* element, HyperGraphElementAction::Parameters* params_){
95  if (typeid(*element).name()!=_typeName)
96  return 0;
97 
98  refreshPropertyPtrs(params_);
99  if (! _previousParams)
100  return this;
101 
102  if (_show && !_show->value())
103  return this;
104 
105  EdgeSE2PointXYBearing* e = static_cast<EdgeSE2PointXYBearing*>(element);
106  VertexSE2* from = static_cast<VertexSE2*>(e->vertex(0));
107  VertexPointXY* to = static_cast<VertexPointXY*>(e->vertex(1));
108  if (! from)
109  return this;
110  double guessRange=5;
111  double theta = e->measurement();
112  Vector2D p(cos(theta)*guessRange, sin(theta)*guessRange);
113  glPushAttrib(GL_ENABLE_BIT|GL_LIGHTING|GL_COLOR);
114  glDisable(GL_LIGHTING);
115  if (!to){
116  p=from->estimate()*p;
117  glColor3f(LANDMARK_EDGE_GHOST_COLOR);
118  glPushAttrib(GL_POINT_SIZE);
119  glPointSize(3);
120  glBegin(GL_POINTS);
121  glVertex3f((float)p.x(),(float)p.y(),0.f);
122  glEnd();
123  glPopAttrib();
124  } else {
125  p=to->estimate();
126  glColor3f(LANDMARK_EDGE_COLOR);
127  }
128  glBegin(GL_LINES);
129  glVertex3f((float)from->estimate().translation().x(),(float)from->estimate().translation().y(),0.f);
130  glVertex3f((float)p.x(),(float)p.y(),0.f);
131  glEnd();
132  glPopAttrib();
133  return this;
134  }
135 #endif
136 
137 } // 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
virtual void initialEstimate(const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *to)
Abstract action that operates on a graph entity.
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
const std::string & name() const
returns the name of an action, e.g "draw"
const Eigen::Rotation2Dd & rotation() const
rotational component
Definition: se2.h:58
EIGEN_MAKE_ALIGNED_OPERATOR_NEW EdgeSE2PointXYBearing()
#define LANDMARK_EDGE_COLOR
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 read(std::istream &is)
read the vertex from a stream, i.e., the internal state of the vertex
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 ...
const EstimateType & estimate() const
return the current estimate of the vertex
Definition: base_vertex.h:99
const Vector2D & translation() const
translational component
Definition: se2.h:54
#define LANDMARK_EDGE_GHOST_COLOR
EIGEN_STRONG_INLINE const Measurement & measurement() const
accessor functions for the measurement represented by the edge
Definition: base_edge.h:75
void setRotation(const Eigen::Rotation2Dd &R_)
Definition: se2.h:59
VertexContainer _vertices
Definition: hyper_graph.h:202