g2o
Loading...
Searching...
No Matches
edge_se3_plane_calib.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_SE3_PLANE_CALIB_H
28#define G2O_EDGE_SE3_PLANE_CALIB_H
29
30#include "g2o/config.h"
33#include "vertex_plane.h"
34
35namespace g2o {
40 : public BaseVariableSizedEdge<3, Plane3D> {
41 public:
45
46 void computeError() {
47 const VertexSE3* v1 = static_cast<const VertexSE3*>(_vertices[0]);
48 const VertexPlane* planeVertex =
49 static_cast<const VertexPlane*>(_vertices[1]);
50 const VertexSE3* offset = static_cast<const VertexSE3*>(_vertices[2]);
51 const Plane3D& plane = planeVertex->estimate();
52 // measurement function: remap the plane in global coordinates
53 Isometry3 w2n = (v1->estimate() * offset->estimate()).inverse();
54 Plane3D localPlane = w2n * plane;
55 _error = localPlane.ominus(_measurement);
56 }
57
58 void setMeasurement(const Plane3D& m) { _measurement = m; }
59
60 virtual bool read(std::istream& is);
61 virtual bool write(std::ostream& os) const;
62};
63
64#ifdef G2O_HAVE_OPENGL
65class EdgeSE3PlaneSensorCalibDrawAction : public DrawAction {
66 public:
67 G2O_TYPES_SLAM3D_ADDONS_API EdgeSE3PlaneSensorCalibDrawAction();
68 G2O_TYPES_SLAM3D_ADDONS_API virtual HyperGraphElementAction* operator()(
69 HyperGraph::HyperGraphElement* element,
70 HyperGraphElementAction::Parameters* params_);
71
72 protected:
73 virtual bool refreshPropertyPtrs(
74 HyperGraphElementAction::Parameters* params_);
75 FloatProperty *_planeWidth, *_planeHeight;
76};
77#endif
78
79} // namespace g2o
80
81#endif
base class to represent an edge connecting an arbitrary number of nodes
const EstimateType & estimate() const
return the current estimate of the vertex
plane measurement that also calibrates an offset for the sensor
void setMeasurement(const Plane3D &m)
Vector3 ominus(const Plane3D &plane)
Definition plane3d.h:90
3D pose Vertex, represented as an Isometry3
Definition vertex_se3.h:50
#define G2O_TYPES_SLAM3D_ADDONS_API
VectorN< 3 > Vector3
Definition eigen_types.h:51
Eigen::Transform< double, 3, Eigen::Isometry, Eigen::ColMajor > Isometry3
Definition eigen_types.h:77