edge_se3_xyzprior.cpp
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 #include "edge_se3_xyzprior.h"
28 
29 namespace rtabmap {
30 
31 EdgeSE3XYZPrior::EdgeSE3XYZPrior() : BaseUnaryEdge<3, Eigen::Vector3d, g2o::VertexSE3>()
32 {
33  information().setIdentity();
34  setMeasurement(Eigen::Vector3d::Zero());
35  _cache = 0;
36  _offsetParam = 0;
37  resizeParameters(1);
38  installParameter(_offsetParam, 0);
39 }
40 
42  assert(_offsetParam);
43  g2o::ParameterVector pv(1);
44  pv[0] = _offsetParam;
45  resolveCache(_cache, (g2o::OptimizableGraph::Vertex*)_vertices[0], "CACHE_SE3_OFFSET", pv);
46  return _cache != 0;
47 }
48 
49 bool EdgeSE3XYZPrior::read(std::istream& is)
50 {
51  int pid;
52  is >> pid;
53  if (!setParameterId(0, pid))
54  return false;
55 
56  // measured keypoint
57  Eigen::Vector3d meas;
58  for (int i = 0; i < 3; i++) is >> meas[i];
59  setMeasurement(meas);
60 
61  // read covariance matrix (upper triangle)
62  if (is.good()) {
63  for (int i = 0; i < 3; i++) {
64  for (int j = i; j < 3; j++) {
65  is >> information()(i,j);
66  if (i != j)
67  information()(j,i) = information()(i,j);
68  }
69  }
70  }
71  return !is.fail();
72 }
73 
74 bool EdgeSE3XYZPrior::write(std::ostream& os) const {
75  os << _offsetParam->id() << " ";
76  for (int i = 0; i < 3; i++) os << measurement()[i] << " ";
77  for (int i = 0; i < 3; i++) {
78  for (int j = i; j < 3; j++) {
79  os << information()(i,j) << " ";
80  }
81  }
82  return os.good();
83 }
84 
86  const g2o::VertexSE3* v = static_cast<const g2o::VertexSE3*>(_vertices[0]);
87  _error = v->estimate().translation() - _measurement;
88 }
89 
91  const g2o::VertexSE3* v = static_cast<const g2o::VertexSE3*>(_vertices[0]);
92  _measurement = v->estimate().translation();
93  return true;
94 }
95 
96 void EdgeSE3XYZPrior::initialEstimate(const g2o::OptimizableGraph::VertexSet& /*from_*/, g2o::OptimizableGraph::Vertex* /*to_*/) {
97  g2o::VertexSE3 *v = static_cast<g2o::VertexSE3*>(_vertices[0]);
98  assert(v && "Vertex for the Prior edge is not set");
99 
100  Eigen::Isometry3d newEstimate = _offsetParam->offset().inverse() * Eigen::Translation3d(measurement());
101  if (_information.block<3,3>(0,0).array().abs().sum() == 0){ // do not set translation, as that part of the information is all zero
102  newEstimate.translation() = v->estimate().translation();
103  }
104  v->setEstimate(newEstimate);
105 }
106 
107 }
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 *)
g2o::CacheSE3Offset * _cache
virtual bool write(std::ostream &os) const
EIGEN_MAKE_ALIGNED_OPERATOR_NEW EdgeSE3XYZPrior()
virtual bool setMeasurementFromState()


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