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"
29 #include <iostream>
30 
31 namespace g2o {
32 namespace deprecated {
33 
34  using namespace std;
35 
36 
37  // point to camera projection, monocular
39  information().setIdentity();
40  _cache = 0;
41  _offsetParam = 0;
44  }
45 
46 
48  assert(_offsetParam);
49  ParameterVector pv(1);
50  pv[0]=_offsetParam;
51  resolveCache(_cache, (OptimizableGraph::Vertex*)_vertices[0],"CACHE_SE3_OFFSET",pv);
52  return _cache != 0;
53  }
54 
55 
56 
57  bool EdgeSE3Prior::read(std::istream& is) {
58  int pid;
59  is >> pid;
60  if (!setParameterId(0, pid))
61  return false;
62  // measured keypoint
63  Vector7d meas;
64  for (int i=0; i<7; i++) is >> meas[i];
65  setMeasurement(SE3Quat(meas));
66  // don't need this if we don't use it in error calculation (???)
67  // information matrix is the identity for features, could be changed to allow arbitrary covariances
68  if (is.bad()) {
69  return false;
70  }
71  for ( int i=0; i<information().rows() && is.good(); i++)
72  for (int j=i; j<information().cols() && is.good(); j++){
73  is >> information()(i,j);
74  if (i!=j)
75  information()(j,i)=information()(i,j);
76  }
77  if (is.bad()) {
78  // we overwrite the information matrix
79  information().setIdentity();
80  }
81  return true;
82  }
83 
84  bool EdgeSE3Prior::write(std::ostream& os) const {
85  os << _offsetParam->id() << " ";
86  for (int i=0; i<7; i++) os << measurement()[i] << " ";
87  for (int i=0; i<information().rows(); i++)
88  for (int j=i; j<information().cols(); j++) {
89  os << information()(i,j) << " ";
90  }
91  return os.good();
92  }
93 
94 
97 
98  _error.head<3>() = delta.translation();
99  // The analytic Jacobians assume the error in this special form (w beeing positive)
100  if (delta.rotation().w() < 0.)
101  _error.tail<3>() = - delta.rotation().vec();
102  else
103  _error.tail<3>() = delta.rotation().vec();
104  }
105 
107  VertexSE3 *from = static_cast<VertexSE3*>(_vertices[0]);
108  Eigen::Isometry3d E;
109  Eigen::Isometry3d Z, X, P;
110  X=from->estimate().rotation().toRotationMatrix();
111  X.translation()=from->estimate().translation();
112  P=_cache->offsetParam()->offset().rotation().toRotationMatrix();
113  P.translation()=_cache->offsetParam()->offset().translation();
114  Z=_measurement.rotation().toRotationMatrix();
115  Z.translation()=_measurement.translation();
117  }
118 
119 
122  return true;
123  }
124 
125 
127  VertexSE3 *v = static_cast<VertexSE3*>(_vertices[0]);
128 
129  SE3Quat newEstimate = _offsetParam->offset().inverse() * measurement();
130  if (_information.block<3,3>(0,0).squaredNorm()==0){ // do not set translation
131  newEstimate.setTranslation(v->estimate().translation());
132  }
133  if (_information.block<3,3>(3,3).squaredNorm()==0){ // do not set rotation
134  newEstimate.setRotation(v->estimate().rotation());
135  }
136  v->setEstimate(newEstimate);
137  }
138 
139 }
140 }
bool installParameter(ParameterType *&p, size_t argNo, int paramId=-1)
const SE3Quat & offset() const
return the offset as SE3Quat
std::set< Vertex * > VertexSet
Definition: hyper_graph.h:136
virtual void initialEstimate(const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *to)
InformationType _information
Definition: base_edge.h:88
Eigen::Matrix< double, 7, 1 > Vector7d
Definition: sim3.h:35
SE3Quat inverse() const
Definition: se3quat.h:120
bool setParameterId(int argNum, int paramId)
virtual void setMeasurement(const SE3Quat &m)
EIGEN_MAKE_ALIGNED_OPERATOR_NEW EdgeSE3Prior()
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
int id() const
Definition: parameter.h:45
const Eigen::Quaterniond & rotation() const
Definition: se3quat.h:97
3D pose Vertex, (x,y,z,qw,qx,qy,qz) the parameterization for the increments constructed is a 6d vecto...
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 setTranslation(const Vector3D &t_)
Definition: se3quat.h:95
void resizeParameters(size_t newSize)
EIGEN_STRONG_INLINE const InformationType & information() const
information matrix of the constraint
Definition: base_edge.h:67
ParameterSE3Offset * _offsetParam
virtual bool write(std::ostream &os) const
write the vertex to a stream
const EstimateType & estimate() const
return the current estimate of the vertex
Definition: base_vertex.h:99
void setRotation(const Eigen::Quaterniond &r_)
Definition: se3quat.h:99
virtual bool read(std::istream &is)
read the vertex from a stream, i.e., the internal state of the vertex
void computeEdgeSE3PriorGradient(Isometry3D &E, const Eigen::MatrixBase< Derived > &JConstRef, const Isometry3D &Z, const Isometry3D &X, const Isometry3D &P=Isometry3D())
EIGEN_STRONG_INLINE const Measurement & measurement() const
accessor functions for the measurement represented by the edge
Definition: base_edge.h:75
const ParameterSE3Offset * offsetParam() const
const Vector3D & translation() const
Definition: se3quat.h:93
VertexContainer _vertices
Definition: hyper_graph.h:202