g2o
Loading...
Searching...
No Matches
edge_se3_prior.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_PRIOR_H_
28#define G2O_EDGE_SE3_PRIOR_H_
29
33#include "vertex_se3.h"
34
35namespace g2o {
43 : public BaseUnaryEdge<6, Isometry3, VertexSE3> {
44 public:
45 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
47 virtual bool read(std::istream& is);
48 virtual bool write(std::ostream& os) const;
49
50 // return the error estimate as a 3-vector
51 void computeError();
52
53 // jacobian
54 virtual void linearizeOplus();
55
56 virtual void setMeasurement(const Isometry3& m) {
57 _measurement = m;
58 _inverseMeasurement = m.inverse();
59 }
60
61 virtual bool setMeasurementData(const double* d) {
62 Eigen::Map<const Vector7> v(d);
63 _measurement = internal::fromVectorQT(v);
64 _inverseMeasurement = _measurement.inverse();
65 return true;
66 }
67
68 virtual bool getMeasurementData(double* d) const {
69 Eigen::Map<Vector7> v(d);
70 v = internal::toVectorQT(_measurement);
71 return true;
72 }
73
74 virtual int measurementDimension() const { return 7; }
75
76 virtual bool setMeasurementFromState();
77
79 const OptimizableGraph::VertexSet& /*from*/,
81 return 1.;
82 }
83
84 virtual void initialEstimate(const OptimizableGraph::VertexSet& from,
86
87 protected:
89 virtual bool resolveCaches();
92};
93
94} // namespace g2o
95#endif
caching the offset related to a vertex
prior for an SE3 element
CacheSE3Offset * _cache
virtual bool setMeasurementData(const double *d)
virtual double initialEstimatePossible(const OptimizableGraph::VertexSet &, OptimizableGraph::Vertex *)
ParameterSE3Offset * _offsetParam
virtual void setMeasurement(const Isometry3 &m)
virtual int measurementDimension() const
virtual bool getMeasurementData(double *d) const
Isometry3 _inverseMeasurement
std::set< Vertex * > VertexSet
A general case Vertex for optimization.
#define G2O_TYPES_SLAM3D_API
Eigen::Transform< double, 3, Eigen::Isometry, Eigen::ColMajor > Isometry3
Definition eigen_types.h:77