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 // Modified by Raúl Mur Artal (2014)
28 // - Added EdgeInverseSim3ProjectXYZ
29 // - Modified VertexSim3Expmap to represent relative transformation between two cameras. Includes calibration of both cameras.
30 
31 #ifndef G2O_SEVEN_DOF_EXPMAP_TYPES
32 #define G2O_SEVEN_DOF_EXPMAP_TYPES
33 
34 #include "../core/base_vertex.h"
35 #include "../core/base_binary_edge.h"
36 #include "types_six_dof_expmap.h"
37 #include "sim3.h"
38 
39 namespace g2o {
40 
41  using namespace Eigen;
42 
48  class VertexSim3Expmap : public BaseVertex<7, Sim3>
49  {
50  public:
51  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
53  virtual bool read(std::istream& is);
54  virtual bool write(std::ostream& os) const;
55 
56  virtual void setToOriginImpl() {
57  _estimate = Sim3();
58  }
59 
60  virtual void oplusImpl(const double* update_)
61  {
62  Eigen::Map<Vector7d> update(const_cast<double*>(update_));
63 
64  if (_fix_scale)
65  update[6] = 0;
66 
67  Sim3 s(update);
68  setEstimate(s*estimate());
69  }
70 
71  Vector2d _principle_point1, _principle_point2;
72  Vector2d _focal_length1, _focal_length2;
73 
74  Vector2d cam_map1(const Vector2d & v) const
75  {
76  Vector2d res;
77  res[0] = v[0]*_focal_length1[0] + _principle_point1[0];
78  res[1] = v[1]*_focal_length1[1] + _principle_point1[1];
79  return res;
80  }
81 
82  Vector2d cam_map2(const Vector2d & v) const
83  {
84  Vector2d res;
85  res[0] = v[0]*_focal_length2[0] + _principle_point2[0];
86  res[1] = v[1]*_focal_length2[1] + _principle_point2[1];
87  return res;
88  }
89 
90  bool _fix_scale;
91 
92 
93  protected:
94  };
95 
99  class EdgeSim3 : public BaseBinaryEdge<7, Sim3, VertexSim3Expmap, VertexSim3Expmap>
100  {
101  public:
102  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
103  EdgeSim3();
104  virtual bool read(std::istream& is);
105  virtual bool write(std::ostream& os) const;
107  {
108  const VertexSim3Expmap* v1 = static_cast<const VertexSim3Expmap*>(_vertices[0]);
109  const VertexSim3Expmap* v2 = static_cast<const VertexSim3Expmap*>(_vertices[1]);
110 
111  Sim3 C(_measurement);
112  Sim3 error_=C*v1->estimate()*v2->estimate().inverse();
113  _error = error_.log();
114  }
115 
118  {
119  VertexSim3Expmap* v1 = static_cast<VertexSim3Expmap*>(_vertices[0]);
120  VertexSim3Expmap* v2 = static_cast<VertexSim3Expmap*>(_vertices[1]);
121  if (from.count(v1) > 0)
122  v2->setEstimate(measurement()*v1->estimate());
123  else
124  v1->setEstimate(measurement().inverse()*v2->estimate());
125  }
126  };
127 
128 
129 
130 class EdgeSim3ProjectXYZ : public BaseBinaryEdge<2, Vector2d, VertexSBAPointXYZ, VertexSim3Expmap>
131 {
132  public:
133  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
135  virtual bool read(std::istream& is);
136  virtual bool write(std::ostream& os) const;
137 
139  {
140  const VertexSim3Expmap* v1 = static_cast<const VertexSim3Expmap*>(_vertices[1]);
141  const VertexSBAPointXYZ* v2 = static_cast<const VertexSBAPointXYZ*>(_vertices[0]);
142 
143  Vector2d obs(_measurement);
144  _error = obs-v1->cam_map1(project(v1->estimate().map(v2->estimate())));
145  }
146 
147  // virtual void linearizeOplus();
148 
149 };
150 
151 
152 class EdgeInverseSim3ProjectXYZ : public BaseBinaryEdge<2, Vector2d, VertexSBAPointXYZ, VertexSim3Expmap>
153 {
154  public:
155  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
157  virtual bool read(std::istream& is);
158  virtual bool write(std::ostream& os) const;
159 
161  {
162  const VertexSim3Expmap* v1 = static_cast<const VertexSim3Expmap*>(_vertices[1]);
163  const VertexSBAPointXYZ* v2 = static_cast<const VertexSBAPointXYZ*>(_vertices[0]);
164 
165  Vector2d obs(_measurement);
166  _error = obs-v1->cam_map2(project(v1->estimate().inverse().map(v2->estimate())));
167  }
168 
169  // virtual void linearizeOplus();
170 
171 };
172 
173 } // end namespace
174 
175 #endif
176 
Definition: sim3.h:41
Vector2d cam_map1(const Vector2d &v) const
std::set< Vertex * > VertexSet
Definition: hyper_graph.h:91
XmlRpcServer s
Sim3 inverse() const
Definition: sim3.h:233
Templatized BaseVertex.
Definition: base_vertex.h:53
Point vertex, XYZ.
Definition: types_sba.h:40
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
virtual void initialEstimate(const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *)
virtual double initialEstimatePossible(const OptimizableGraph::VertexSet &, OptimizableGraph::Vertex *)
virtual void oplusImpl(const double *update_)
TFSIMD_FORCE_INLINE Quaternion inverse(const Quaternion &q)
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:104
A general case Vertex for optimization.
Vector2d project(const Vector3d &)
Definition: se3_ops.h:50
7D edge between two Vertex7
Vector7d log() const
Definition: sim3.h:148
const EstimateType & estimate() const
return the current estimate of the vertex
Definition: base_vertex.h:102
Vector3d map(const Vector3d &xyz) const
Definition: sim3.h:144
virtual void setToOriginImpl()
sets the node to the origin (used in the multilevel stuff)
Vector2d cam_map2(const Vector2d &v) const


orb_slam2_ros
Author(s):
autogenerated on Wed Apr 21 2021 02:53:05