edge_xyz_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 
32 #ifndef G2O_EDGE_XYZ_PRIOR_H_
33 #define G2O_EDGE_XYZ_PRIOR_H_
34 
35 #include "g2o/core/base_unary_edge.h"
36 #include "g2o/types/slam3d/vertex_pointxyz.h"
37 
38 namespace g2o {
39 
40 using namespace Eigen;
41 
48  class EdgeXYZPrior : public BaseUnaryEdge<3, Vector3d, VertexPointXYZ> {
49  public:
50  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
51  EdgeXYZPrior();
52  virtual bool read(std::istream& is);
53  virtual bool write(std::ostream& os) const;
54 
55  void computeError();
56 
57  // jacobian
58  virtual void linearizeOplus();
59 
60  virtual void setMeasurement(const Vector3d& m){
61  _measurement = m;
62  }
63 
64  virtual bool setMeasurementData(const double* d){
65  Eigen::Map<const Vector3d> v(d);
66  _measurement = v;
67  return true;
68  }
69 
70  virtual bool getMeasurementData(double* d) const{
71  Eigen::Map<Vector3d> v(d);
72  v = _measurement;
73  return true;
74  }
75 
76  virtual int measurementDimension() const { return 3; }
77 
78  virtual bool setMeasurementFromState() ;
79 
80  virtual double initialEstimatePossible(const OptimizableGraph::VertexSet& /*from*/,
81  OptimizableGraph::Vertex* /*to*/) {
82  return 0;
83  }
84  };
85 
86  EdgeXYZPrior::EdgeXYZPrior() : BaseUnaryEdge<3, Vector3d, VertexPointXYZ>() {
87  information().setIdentity();
88  }
89 
90  bool EdgeXYZPrior::read(std::istream& is) {
91  // read measurement
92  Vector3d meas;
93  for (int i=0; i<3; i++) is >> meas[i];
94  setMeasurement(meas);
95  // read covariance matrix (upper triangle)
96  if (is.good()) {
97  for ( int i=0; i<information().rows(); i++)
98  for (int j=i; j<information().cols(); j++){
99  is >> information()(i,j);
100  if (i!=j)
101  information()(j,i)=information()(i,j);
102  }
103  }
104  return !is.fail();
105  }
106 
107  bool EdgeXYZPrior::write(std::ostream& os) const {
108  for (int i = 0; i<3; i++) os << measurement()[i] << " ";
109  for (int i=0; i<information().rows(); i++)
110  for (int j=i; j<information().cols(); j++) {
111  os << information()(i,j) << " ";
112  }
113  return os.good();
114  }
115 
117  const VertexPointXYZ* v = static_cast<const VertexPointXYZ*>(_vertices[0]);
118  _error = v->estimate() - _measurement;
119  }
120 
122  _jacobianOplusXi = Matrix3d::Identity();
123  }
124 
126  const VertexPointXYZ* v = static_cast<const VertexPointXYZ*>(_vertices[0]);
127  _measurement = v->estimate();
128  return true;
129  }
130 }
131 #endif
virtual bool read(std::istream &is)
virtual bool setMeasurementFromState()
prior for an XYZ vertex (VertexPointXYZ)
virtual double initialEstimatePossible(const OptimizableGraph::VertexSet &, OptimizableGraph::Vertex *)
virtual bool getMeasurementData(double *d) const
virtual void setMeasurement(const Vector3d &m)
EIGEN_MAKE_ALIGNED_OPERATOR_NEW EdgeXYZPrior()
virtual bool setMeasurementData(const double *d)
virtual bool write(std::ostream &os) const
virtual void linearizeOplus()
virtual int measurementDimension() const


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Jan 23 2023 03:37:28