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