g2o
types_seven_dof_expmap.h
Go to the documentation of this file.
1 // g2o - General Graph Optimization
2 // Copyright (C) 2011 H. Strasdat
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 G2O_SEVEN_DOF_EXPMAP_TYPES
28 #define G2O_SEVEN_DOF_EXPMAP_TYPES
29 
30 #include "g2o/core/base_vertex.h"
33 #include "sim3.h"
34 
35 namespace g2o {
36 
37 
43  class VertexSim3Expmap : public BaseVertex<7, Sim3>
44  {
45  public:
48  virtual bool read(std::istream& is);
49  virtual bool write(std::ostream& os) const;
50 
51  virtual void setToOriginImpl() {
52  _estimate = Sim3();
53  }
54 
55  virtual void oplusImpl(const double* update_)
56  {
57  Eigen::Map<Vector7d> update(const_cast<double*>(update_));
58 
59  if (_fix_scale)
60  update[6] = 0;
61 
62  Sim3 s(update);
63  setEstimate(s*estimate());
64  }
65 
68 
69  Vector2D cam_map(const Vector2D & v) const
70  {
71  Vector2D res;
72  res[0] = v[0]*_focal_length[0] + _principle_point[0];
73  res[1] = v[1]*_focal_length[1] + _principle_point[1];
74  return res;
75  }
76 
77  bool _fix_scale;
78 
79 
80  protected:
81  };
82 
86  class EdgeSim3 : public BaseBinaryEdge<7, Sim3, VertexSim3Expmap, VertexSim3Expmap>
87  {
88  public:
90  EdgeSim3();
91  virtual bool read(std::istream& is);
92  virtual bool write(std::ostream& os) const;
93  void computeError()
94  {
95  const VertexSim3Expmap* v1 = static_cast<const VertexSim3Expmap*>(_vertices[0]);
96  const VertexSim3Expmap* v2 = static_cast<const VertexSim3Expmap*>(_vertices[1]);
97 
98  Sim3 C(_measurement);
99  Sim3 error_=C*v1->estimate()*v2->estimate().inverse();
100  _error = error_.log();
101  }
102 
105  {
106  VertexSim3Expmap* v1 = static_cast<VertexSim3Expmap*>(_vertices[0]);
107  VertexSim3Expmap* v2 = static_cast<VertexSim3Expmap*>(_vertices[1]);
108  if (from.count(v1) > 0)
109  v2->setEstimate(measurement()*v1->estimate());
110  else
111  v1->setEstimate(measurement().inverse()*v2->estimate());
112  }
113  };
114 
115 
116 
117 class EdgeSim3ProjectXYZ : public BaseBinaryEdge<2, Vector2D, VertexSBAPointXYZ, VertexSim3Expmap>
118 {
119  public:
122  virtual bool read(std::istream& is);
123  virtual bool write(std::ostream& os) const;
124 
126  {
127  const VertexSim3Expmap* v1 = static_cast<const VertexSim3Expmap*>(_vertices[1]);
128  const VertexSBAPointXYZ* v2 = static_cast<const VertexSBAPointXYZ*>(_vertices[0]);
129 
130  Vector2D obs(_measurement);
131  _error = obs-v1->cam_map(project(v1->estimate().map(v2->estimate())));
132  }
133 
134  // virtual void linearizeOplus();
135 
136 };
137 
138 } // end namespace
139 
140 #endif
Eigen::Matrix< double, 2, 1, Eigen::ColMajor > Vector2D
Definition: eigen_types.h:45
Definition: sim3.h:38
virtual bool read(std::istream &is)
read the vertex from a stream, i.e., the internal state of the vertex
std::set< Vertex * > VertexSet
Definition: hyper_graph.h:136
virtual bool write(std::ostream &os) const
write the vertex to a stream
Vector2D cam_map(const Vector2D &v) const
Sim3 inverse() const
Definition: sim3.h:220
Templatized BaseVertex.
Definition: base_vertex.h:50
Point vertex, XYZ.
Definition: types_sba.h:137
virtual void initialEstimate(const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *)
Eigen::Vector3d map(const Eigen::Vector3d &xyz) const
Definition: sim3.h:138
virtual double initialEstimatePossible(const OptimizableGraph::VertexSet &, OptimizableGraph::Vertex *)
virtual void oplusImpl(const double *update_)
stuff to open files and other unsorted components Sim3
Sim3 Vertex, (x,y,z,qw,qx,qy,qz) the parameterization for the increments constructed is a 7d vector (...
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.
7D edge between two Vertex7
Vector7d log() const
Definition: sim3.h:142
const EstimateType & estimate() const
return the current estimate of the vertex
Definition: base_vertex.h:99
G2O_TYPES_SLAM3D_API Vector2D project(const Vector3D &)
Definition: se3_ops.h:50
virtual void setToOriginImpl()
sets the node to the origin (used in the multilevel stuff)