g2o
Loading...
Searching...
No Matches
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
30#include "g2o/config.h"
33#include "vertex_plane.h"
34
35namespace g2o {
36
38 : public BaseBinaryEdge<4, Vector4, VertexPlane, VertexPlane> {
39 public:
40 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
41 EdgePlane();
42
43 void computeError() {
44 const VertexPlane* v1 = static_cast<const VertexPlane*>(_vertices[0]);
45 const VertexPlane* v2 = static_cast<const VertexPlane*>(_vertices[1]);
46 _error =
47 (v2->estimate().toVector() - v1->estimate().toVector()) - _measurement;
48 }
49 virtual bool read(std::istream& is);
50 virtual bool write(std::ostream& os) const;
51
52 virtual void setMeasurement(const Vector4& m) { _measurement = m; }
53
54 virtual bool setMeasurementData(const double* d) {
55 Eigen::Map<const Vector4> m(d);
56 _measurement = m;
57 return true;
58 }
59
60 virtual bool getMeasurementData(double* d) const {
61 Eigen::Map<Vector4> m(d);
62 m = _measurement;
63 return true;
64 }
65
66 virtual int measurementDimension() const { return 4; }
67
68 virtual bool setMeasurementFromState() {
69 const VertexPlane* v1 = static_cast<const VertexPlane*>(_vertices[0]);
70 const VertexPlane* v2 = static_cast<const VertexPlane*>(_vertices[1]);
71 _measurement = (v2->estimate().toVector()) - v1->estimate().toVector();
72
73 return true;
74 }
75
76#if 0
77 virtual void linearizeOplus();
78#endif
79};
80
81} // namespace g2o
82
83#endif
const EstimateType & estimate() const
return the current estimate of the vertex
virtual bool setMeasurementData(const double *d)
Definition edge_plane.h:54
virtual bool setMeasurementFromState()
Definition edge_plane.h:68
void computeError()
Definition edge_plane.h:43
virtual void setMeasurement(const Vector4 &m)
Definition edge_plane.h:52
virtual int measurementDimension() const
Definition edge_plane.h:66
virtual bool getMeasurementData(double *d) const
Definition edge_plane.h:60
Vector4 toVector() const
Definition plane3d.h:48
#define G2O_TYPES_SLAM3D_ADDONS_API
VectorN< 4 > Vector4
Definition eigen_types.h:52