g2o
edge_se3_quat.h
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 #ifndef G2O_DEPRECATED_EDGE_SE3_QUAT_
28 #define G2O_DEPRECATED_EDGE_SE3_QUAT_
29 
30 #include "g2o/config.h"
31 #include "g2o/core/base_vertex.h"
35 
36 #define EDGE_SE3_QUAT_ANALYTIC_JACOBIAN
37 
38 #include "vertex_se3_quat.h"
39 
41 
42 namespace g2o {
43 namespace deprecated {
44 
48  class G2O_DEPRECATED_TYPES_SLAM3D_API EdgeSE3 : public BaseBinaryEdge<6, SE3Quat, VertexSE3, VertexSE3>
49 {
50  public:
51  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
52  EdgeSE3();
53  void computeError()
54  {
55  const VertexSE3* v1 = dynamic_cast<const VertexSE3*>(_vertices[0]);
56  const VertexSE3* v2 = dynamic_cast<const VertexSE3*>(_vertices[1]);
57  SE3Quat delta = _inverseMeasurement * (v1->estimate().inverse()*v2->estimate());
58  _error.head<3>() = delta.translation();
59  // The analytic Jacobians assume the error in this special form (w beeing positive)
60  if (delta.rotation().w() < 0.)
61  _error.tail<3>() = - delta.rotation().vec();
62  else
63  _error.tail<3>() = delta.rotation().vec();
64  }
65 
66  virtual void setMeasurement(const SE3Quat& m){
67  _measurement = m;
68  _inverseMeasurement = m.inverse();
69  }
70 
71  virtual bool setMeasurementData(const double* d){
72  Eigen::Map<const Vector7d> v(d);
73  _measurement.fromVector(v);
74  _inverseMeasurement = _measurement.inverse();
75  return true;
76  }
77 
78  virtual bool getMeasurementData(double* d) const{
79  Eigen::Map<Vector7d> v(d);
80  v = _measurement.toVector();
81  return true;
82  }
83 
84  virtual int measurementDimension() const {return 7;}
85 
86  virtual bool setMeasurementFromState() ;
87 
88  virtual bool read(std::istream& is);
89  virtual bool write(std::ostream& os) const;
90 
92  virtual void initialEstimate(const OptimizableGraph::VertexSet& from, OptimizableGraph::Vertex* to);
93 
94 #ifdef EDGE_SE3_QUAT_ANALYTIC_JACOBIAN
95  virtual void linearizeOplus();
96 #endif
97  protected:
99 };
100 
102  public:
104  virtual HyperGraphElementAction* operator()(HyperGraph::HyperGraphElement* element,
106  };
107 
108 #ifdef G2O_HAVE_OPENGL
109  class EdgeSE3DrawAction: public DrawAction{
110  public:
111  EdgeSE3DrawAction();
112  virtual HyperGraphElementAction* operator()(HyperGraph::HyperGraphElement* element,
114  };
115 #endif
116 
117 } // end namespace
118 } // end namespace
119 
120 #endif
Abstract action that operates on a graph entity.
std::set< Vertex * > VertexSet
Definition: hyper_graph.h:136
virtual double initialEstimatePossible(const OptimizableGraph::VertexSet &, OptimizableGraph::Vertex *)
Definition: edge_se3_quat.h:91
SE3Quat inverse() const
Definition: se3quat.h:120
virtual bool setMeasurementData(const double *d)
Definition: edge_se3_quat.h:71
#define G2O_DEPRECATED_TYPES_SLAM3D_API
3D edge between two VertexSE3
Definition: edge_se3_quat.h:48
const Eigen::Quaterniond & rotation() const
Definition: se3quat.h:97
3D pose Vertex, (x,y,z,qw,qx,qy,qz) the parameterization for the increments constructed is a 6d vecto...
A general case Vertex for optimization.
virtual int measurementDimension() const
Definition: edge_se3_quat.h:84
const EstimateType & estimate() const
return the current estimate of the vertex
Definition: base_vertex.h:99
virtual void setMeasurement(const SE3Quat &m)
Definition: edge_se3_quat.h:66
virtual bool getMeasurementData(double *d) const
Definition: edge_se3_quat.h:78
const Vector3D & translation() const
Definition: se3quat.h:93