g2o
edge_se3_prior.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_prior.h"
28 #include "isometry3d_gradients.h"
29 #include <iostream>
30 
31 namespace g2o {
32  using namespace std;
33 
34  // point to camera projection, monocular
36  setMeasurement(Isometry3D::Identity());
37  information().setIdentity();
38  _cache = 0;
39  _offsetParam = 0;
42  }
43 
44 
46  assert(_offsetParam);
47  ParameterVector pv(1);
48  pv[0]=_offsetParam;
49  resolveCache(_cache, (OptimizableGraph::Vertex*)_vertices[0],"CACHE_SE3_OFFSET",pv);
50  return _cache != 0;
51  }
52 
53 
54 
55  bool EdgeSE3Prior::read(std::istream& is) {
56  int pid;
57  is >> pid;
58  if (!setParameterId(0, pid))
59  return false;
60  // measured keypoint
61  Vector7d meas;
62  for (int i=0; i<7; i++) is >> meas[i];
64  // don't need this if we don't use it in error calculation (???)
65  // information matrix is the identity for features, could be changed to allow arbitrary covariances
66  if (is.bad()) {
67  return false;
68  }
69  for ( int i=0; i<information().rows() && is.good(); i++)
70  for (int j=i; j<information().cols() && is.good(); j++){
71  is >> information()(i,j);
72  if (i!=j)
73  information()(j,i)=information()(i,j);
74  }
75  if (is.bad()) {
76  // we overwrite the information matrix
77  information().setIdentity();
78  }
79  return true;
80  }
81 
82  bool EdgeSE3Prior::write(std::ostream& os) const {
83  os << _offsetParam->id() << " ";
85  for (int i=0; i<7; i++) os << meas[i] << " ";
86  for (int i=0; i<information().rows(); i++)
87  for (int j=i; j<information().cols(); j++) {
88  os << information()(i,j) << " ";
89  }
90  return os.good();
91  }
92 
93 
97  }
98 
100  VertexSE3 *from = static_cast<VertexSE3*>(_vertices[0]);
101  Isometry3D E;
102  Isometry3D Z, X, P;
103  X=from->estimate();
104  P=_cache->offsetParam()->offset();
105  Z=_measurement;
107  }
108 
109 
112  return true;
113  }
114 
115 
117  VertexSE3 *v = static_cast<VertexSE3*>(_vertices[0]);
118  assert(v && "Vertex for the Prior edge is not set");
119 
120  Isometry3D newEstimate = _offsetParam->offset().inverse() * measurement();
121  if (_information.block<3,3>(0,0).array().abs().sum() == 0){ // do not set translation, as that part of the information is all zero
122  newEstimate.translation()=v->estimate().translation();
123  }
124  if (_information.block<3,3>(3,3).array().abs().sum() == 0){ // do not set rotation, as that part of the information is all zero
125  newEstimate.matrix().block<3,3>(0,0) = internal::extractRotation(v->estimate());
126  }
127  v->setEstimate(newEstimate);
128  }
129 
130 }
bool installParameter(ParameterType *&p, size_t argNo, int paramId=-1)
Isometry3D fromVectorQT(const Vector7d &v)
const ParameterSE3Offset * offsetParam() const
std::set< Vertex * > VertexSet
Definition: hyper_graph.h:136
virtual bool setMeasurementFromState()
const Isometry3D & offset() const
rotation of the offset as 3x3 rotation matrix
ParameterSE3Offset * _offsetParam
virtual bool write(std::ostream &os) const
write the vertex to a stream
InformationType _information
Definition: base_edge.h:88
Eigen::Matrix< double, 7, 1 > Vector7d
Definition: sim3.h:35
virtual bool resolveCaches()
virtual bool read(std::istream &is)
read the vertex from a stream, i.e., the internal state of the vertex
bool setParameterId(int argNum, int paramId)
void resolveCache(CacheType *&cache, OptimizableGraph::Vertex *, const std::string &_type, const ParameterVector &parameters)
Definition: cache.h:122
std::vector< Parameter * > ParameterVector
Definition: parameter.h:52
Eigen::Transform< double, 3, Eigen::Isometry, Eigen::ColMajor > Isometry3D
Definition: eigen_types.h:66
int id() const
Definition: parameter.h:45
Vector6d toVectorMQT(const Isometry3D &t)
Isometry3D::ConstLinearPart extractRotation(const Isometry3D &A)
void setEstimate(const EstimateType &et)
set the estimate for the vertex also calls updateCache()
Definition: base_vertex.h:101
A general case Vertex for optimization.
void resizeParameters(size_t newSize)
EIGEN_STRONG_INLINE const InformationType & information() const
information matrix of the constraint
Definition: base_edge.h:67
const Isometry3D & n2w() const
Isometry3D _inverseMeasurement
const EstimateType & estimate() const
return the current estimate of the vertex
Definition: base_vertex.h:99
3D pose Vertex, represented as an Isometry3D
Definition: vertex_se3.h:50
virtual void setMeasurement(const Isometry3D &m)
void computeEdgeSE3PriorGradient(Isometry3D &E, const Eigen::MatrixBase< Derived > &JConstRef, const Isometry3D &Z, const Isometry3D &X, const Isometry3D &P=Isometry3D())
CacheSE3Offset * _cache
Vector7d toVectorQT(const Isometry3D &t)
virtual void linearizeOplus()
EIGEN_STRONG_INLINE const Measurement & measurement() const
accessor functions for the measurement represented by the edge
Definition: base_edge.h:75
EIGEN_MAKE_ALIGNED_OPERATOR_NEW EdgeSE3Prior()
virtual void initialEstimate(const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *to)
VertexContainer _vertices
Definition: hyper_graph.h:202