g2o
vertex_se3_quat.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 "vertex_se3_quat.h"
28 #include "g2o/core/factory.h"
29 
30 #ifdef G2O_HAVE_OPENGL
32 #endif
33 
34 #include <iostream>
35 #include "g2o/core/cache.h"
36 
37 using namespace Eigen;
38 
39 namespace g2o {
40 namespace deprecated {
41 
42  VertexSE3::VertexSE3() :
43  BaseVertex<6, SE3Quat>()
44  {
45  updateCache();
46  }
47 
48  bool VertexSE3::read(std::istream& is)
49  {
50 
51  Vector7d est;
52  for (int i=0; i<7; i++)
53  is >> est[i];
54  setEstimate(SE3Quat(est));
55  updateCache();
56  return true;
57  }
58 
59  bool VertexSE3::write(std::ostream& os) const
60  {
61  for (int i=0; i<7; i++)
62  os << estimate()[i] << " ";
63  return os.good();
64  }
65 
67 
69  if (typeid(*element).name()!=_typeName)
70  return 0;
72  if (!params->os){
73  std::cerr << __PRETTY_FUNCTION__ << ": warning, no valid os specified" << std::endl;
74  return 0;
75  }
76 
77  VertexSE3* v = static_cast<VertexSE3*>(element);
78  *(params->os) << v->estimate().translation().x() << " "
79  << v->estimate().translation().y() << " "
80  << v->estimate().translation().z() << " ";
81  *(params->os) << v->estimate().rotation().x() << " "
82  << v->estimate().rotation().y() << " "
83  << v->estimate().rotation().z() << " " << std::endl;
84  return this;
85  }
86 
87 #ifdef G2O_HAVE_OPENGL
88  void drawTriangle(float xSize, float ySize){
89  Vector3f p[3];
90  glBegin(GL_TRIANGLES);
91  p[0] << 0., 0., 0.;
92  p[1] << -xSize, ySize, 0.;
93  p[2] << -xSize, -ySize, 0.;
94  for (int i = 1; i < 2; ++i) {
95  Vector3f normal = (p[i] - p[0]).cross(p[i+1] - p[0]);
96  glNormal3f(normal.x(), normal.y(), normal.z());
97  glVertex3f(p[0].x(), p[0].y(), p[0].z());
98  glVertex3f(p[i].x(), p[i].y(), p[i].z());
99  glVertex3f(p[i+1].x(), p[i+1].y(), p[i+1].z());
100  }
101  glEnd();
102  }
103 
104  VertexSE3DrawAction::VertexSE3DrawAction(): DrawAction(typeid(VertexSE3).name()){
105  _cacheDrawActions = 0;
106  }
107 
108  bool VertexSE3DrawAction::refreshPropertyPtrs(HyperGraphElementAction::Parameters* params_){
109  if (!DrawAction::refreshPropertyPtrs(params_))
110  return false;
111  if (_previousParams){
112  _triangleX = _previousParams->makeProperty<FloatProperty>(_typeName + "::TRIANGLE_X", .2f);
113  _triangleY = _previousParams->makeProperty<FloatProperty>(_typeName + "::TRIANGLE_Y", .05f);
114  } else {
115  _triangleX = 0;
116  _triangleY = 0;
117  }
118  return true;
119  }
120 
121  HyperGraphElementAction* VertexSE3DrawAction::operator()(HyperGraph::HyperGraphElement* element,
123  if (typeid(*element).name()!=_typeName)
124  return 0;
125  if (! _cacheDrawActions){
126  _cacheDrawActions = HyperGraphActionLibrary::instance()->actionByName("draw");
127  }
128 
129  refreshPropertyPtrs(params_);
130  if (! _previousParams)
131  return this;
132 
133  if (_show && !_show->value())
134  return this;
135 
136  VertexSE3* that = static_cast<VertexSE3*>(element);
137 
138  glColor3f(0.5f,0.5f,0.8f);
139  glPushMatrix();
140  glTranslatef((float)that->estimate().translation().x(),(float)that->estimate().translation().y(),(float)that->estimate().translation().z());
141  AngleAxisd aa(that->estimate().rotation());
142  glRotatef((float)RAD2DEG(aa.angle()),(float)aa.axis().x(),(float)aa.axis().y(),(float)aa.axis().z());
143  if (_triangleX && _triangleY){
144  drawTriangle(_triangleX->value(), _triangleY->value());
145  }
146  CacheContainer* caches=that->cacheContainer();
147  if (caches){
148  for (CacheContainer::iterator it=caches->begin(); it!=caches->end(); it++){
149  Cache* c = it->second;
150  (*_cacheDrawActions)(c, params_);
151  }
152  }
153  HyperGraph::Data* d=that->userData();
154  while (d && _cacheDrawActions ){
155  (*_cacheDrawActions)(d, params_);
156  d=d->next();
157  }
158  glPopMatrix();
159  return this;
160  }
161 #endif
162 
163 }
164 }
const Data * next() const
Definition: hyper_graph.h:106
#define __PRETTY_FUNCTION__
Definition: macros.h:89
data packet for a vertex. Extend this class to store in the vertices the potential additional informa...
Definition: hyper_graph.h:97
const Data * userData() const
the user data associated with this vertex
Definition: hyper_graph.h:126
Abstract action that operates on a graph entity.
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 ...
Templatized BaseVertex.
Definition: base_vertex.h:50
Eigen::Matrix< double, 7, 1 > Vector7d
Definition: sim3.h:35
const std::string & name() const
returns the name of an action, e.g "draw"
static HyperGraphActionLibrary * instance()
return the single instance of the HyperGraphActionLibrary
const Eigen::Quaterniond & rotation() const
Definition: se3quat.h:97
HyperGraphElementAction * actionByName(const std::string &name)
3D pose Vertex, (x,y,z,qw,qx,qy,qz) the parameterization for the increments constructed is a 6d vecto...
void setEstimate(const EstimateType &et)
set the estimate for the vertex also calls updateCache()
Definition: base_vertex.h:101
const EstimateType & estimate() const
return the current estimate of the vertex
Definition: base_vertex.h:99
virtual bool refreshPropertyPtrs(HyperGraphElementAction::Parameters *params_)
virtual bool write(std::ostream &os) const
write the vertex to a stream
virtual bool read(std::istream &is)
read the vertex from a stream, i.e., the internal state of the vertex
#define RAD2DEG(x)
Definition: macros.h:35
const Vector3D & translation() const
Definition: se3quat.h:93