edge_se3_xyzprior.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 RTAB_G2O_EDGE_SE3_PRIOR_XYZ_H
28 #define RTAB_G2O_EDGE_SE3_PRIOR_XYZ_H
29 
30 #include "g2o/types/slam3d/vertex_se3.h"
31 #include "g2o/core/base_unary_edge.h"
32 #include "g2o/types/slam3d/parameter_se3_offset.h"
33 
34 namespace rtabmap {
35 
39 class EdgeSE3XYZPrior : public g2o::BaseUnaryEdge<3, Eigen::Vector3d, g2o::VertexSE3>
40 {
41 public:
42  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
44 
45  virtual void setMeasurement(const Eigen::Vector3d& m) {
46  _measurement = m;
47  }
48 
49  virtual bool setMeasurementData(const double * d) {
50  Eigen::Map<const Eigen::Vector3d> v(d);
51  _measurement = v;
52  return true;
53  }
54 
55  virtual bool getMeasurementData(double* d) const {
56  Eigen::Map<Eigen::Vector3d> v(d);
57  v = _measurement;
58  return true;
59  }
60 
61  virtual int measurementDimension() const {return 3;}
62 
63  virtual bool read(std::istream& is);
64  virtual bool write(std::ostream& os) const;
65  virtual void computeError();
66  virtual bool setMeasurementFromState();
67 
68  virtual double initialEstimatePossible(const g2o::OptimizableGraph::VertexSet& /*from*/, g2o::OptimizableGraph::Vertex* /*to*/) {return 1.;}
69  virtual void initialEstimate(const g2o::OptimizableGraph::VertexSet& /*from_*/, g2o::OptimizableGraph::Vertex* /*to_*/);
70 
71  const g2o::ParameterSE3Offset* offsetParameter() { return _offsetParam; }
72 
73 protected:
74  virtual bool resolveCaches();
75  g2o::ParameterSE3Offset* _offsetParam;
76  g2o::CacheSE3Offset* _cache;
77 };
78 
79 }
80 
81 #endif
virtual bool read(std::istream &is)
g2o::ParameterSE3Offset * _offsetParam
virtual void setMeasurement(const Eigen::Vector3d &m)
virtual void initialEstimate(const g2o::OptimizableGraph::VertexSet &, g2o::OptimizableGraph::Vertex *)
Prior for a 3D pose with constraints only in xyz direction.
virtual bool setMeasurementData(const double *d)
g2o::CacheSE3Offset * _cache
virtual bool write(std::ostream &os) const
virtual bool getMeasurementData(double *d) const
const g2o::ParameterSE3Offset * offsetParameter()
EIGEN_MAKE_ALIGNED_OPERATOR_NEW EdgeSE3XYZPrior()
virtual bool setMeasurementFromState()
virtual double initialEstimatePossible(const g2o::OptimizableGraph::VertexSet &, g2o::OptimizableGraph::Vertex *)
virtual int measurementDimension() const


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Dec 14 2020 03:34:58