g2o
edge_plane.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_EDGE_PLANE3D_H
28 #define G2O_EDGE_PLANE3D_H
29 
31 #include "vertex_plane.h"
32 #include "g2o/config.h"
34 
35 namespace g2o
36 {
37 
38 class G2O_TYPES_SLAM3D_ADDONS_API EdgePlane : public BaseBinaryEdge<4, Vector4D, VertexPlane, VertexPlane>
39 {
40 public:
41  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
42  EdgePlane();
43 
44  void computeError()
45  {
46  const VertexPlane* v1 = static_cast<const VertexPlane*>(_vertices[0]);
47  const VertexPlane* v2 = static_cast<const VertexPlane*>(_vertices[1]);
48  _error = (v2->estimate().toVector() - v1->estimate().toVector() ) - _measurement;
49  }
50  virtual bool read(std::istream& is);
51  virtual bool write(std::ostream& os) const;
52 
53  virtual void setMeasurement(const Vector4D& m){
54  _measurement = m;
55  }
56 
57  virtual bool setMeasurementData(const double* d){
58  Eigen::Map<const Vector4D> m(d);
59  _measurement=m;
60  return true;
61  }
62 
63  virtual bool getMeasurementData(double* d) const {
64  Eigen::Map<Vector4D> m(d);
65  m=_measurement;
66  return true;
67  }
68 
69  virtual int measurementDimension() const {return 4;}
70 
71  virtual bool setMeasurementFromState() {
72 
73  const VertexPlane* v1 = static_cast<const VertexPlane*>(_vertices[0]);
74  const VertexPlane* v2 = static_cast<const VertexPlane*>(_vertices[1]);
75  _measurement = (v2->estimate().toVector())-v1->estimate().toVector();
76 
77  return true;
78  }
79 
80 
82 #if 0
83 #ifndef NUMERIC_JACOBIAN_THREE_D_TYPES
84  virtual void linearizeOplus();
85 #endif
86 #endif
87 };
88 
89 
90 } // end namespace
91 
92 #endif
virtual double initialEstimatePossible(const OptimizableGraph::VertexSet &, OptimizableGraph::Vertex *)
Definition: edge_plane.h:81
virtual bool setMeasurementFromState()
Definition: edge_plane.h:71
Eigen::Matrix< double, 4, 1, Eigen::ColMajor > Vector4D
Definition: eigen_types.h:47
std::set< Vertex * > VertexSet
Definition: hyper_graph.h:136
virtual int measurementDimension() const
Definition: edge_plane.h:69
A general case Vertex for optimization.
void computeError()
Definition: edge_plane.h:44
virtual void setMeasurement(const Vector4D &m)
Definition: edge_plane.h:53
const EstimateType & estimate() const
return the current estimate of the vertex
Definition: base_vertex.h:99
virtual bool setMeasurementData(const double *d)
Definition: edge_plane.h:57
#define G2O_TYPES_SLAM3D_ADDONS_API
virtual bool getMeasurementData(double *d) const
Definition: edge_plane.h:63
Eigen::Vector4d toVector() const
Definition: plane3d.h:53