g2o
Loading...
Searching...
No Matches
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#include "g2o/config.h"
33#include "sim3.h"
34
35#ifdef _MSC_VER
36// We are using a Microsoft compiler:
37#ifdef G2O_SHARED_LIBS
38#ifdef types_sim3_EXPORTS
39#define G2O_TYPES_SIM3_API __declspec(dllexport)
40#else
41#define G2O_TYPES_SIM3_API __declspec(dllimport)
42#endif
43#else
44#define G2O_TYPES_SIM3_API
45#endif
46
47#else
48// Not Microsoft compiler so set empty definition:
49#define G2O_TYPES_SIM3_API
50#endif
51namespace g2o {
52
61 public:
64 virtual bool read(std::istream& is);
65 virtual bool write(std::ostream& os) const;
66
67 virtual void setToOriginImpl() { _estimate = Sim3(); }
68
69 virtual void oplusImpl(const double* update_) {
70 Eigen::Map<Vector7> update(const_cast<double*>(update_));
71
72 if (_fix_scale) update[6] = 0;
73
74 Sim3 s(update);
75 setEstimate(s * estimate());
76 }
77
78 Vector2 _principle_point1, _principle_point2;
79 Vector2 _focal_length1, _focal_length2;
80
81 Vector2 cam_map1(const Vector2& v) const {
82 Vector2 res;
83 res[0] = v[0] * _focal_length1[0] + _principle_point1[0];
84 res[1] = v[1] * _focal_length1[1] + _principle_point1[1];
85 return res;
86 }
87
88 Vector2 cam_map2(const Vector2& v) const {
89 Vector2 res;
90 res[0] = v[0] * _focal_length2[0] + _principle_point2[0];
91 res[1] = v[1] * _focal_length2[1] + _principle_point2[1];
92 return res;
93 }
94
96
97 protected:
98};
99
104 : public BaseBinaryEdge<7, Sim3, VertexSim3Expmap, VertexSim3Expmap> {
105 public:
106 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
107 EdgeSim3();
108 virtual bool read(std::istream& is);
109 virtual bool write(std::ostream& os) const;
111 const VertexSim3Expmap* v1 =
112 static_cast<const VertexSim3Expmap*>(_vertices[0]);
113 const VertexSim3Expmap* v2 =
114 static_cast<const VertexSim3Expmap*>(_vertices[1]);
115
116 Sim3 C(_measurement);
117 Sim3 error_ = C * v1->estimate() * v2->estimate().inverse();
118 _error = error_.log();
119 }
120
123 return 1.;
124 }
126 OptimizableGraph::Vertex* /*to*/) {
127 VertexSim3Expmap* v1 = static_cast<VertexSim3Expmap*>(_vertices[0]);
128 VertexSim3Expmap* v2 = static_cast<VertexSim3Expmap*>(_vertices[1]);
129 if (from.count(v1) > 0)
130 v2->setEstimate(measurement() * v1->estimate());
131 else
132 v1->setEstimate(measurement().inverse() * v2->estimate());
133 }
134#if G2O_SIM3_JACOBIAN
135 virtual void linearizeOplus();
136#endif
137};
138
139
141 : public BaseBinaryEdge<2, Vector2, VertexPointXYZ, VertexSim3Expmap> {
142 public:
143 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
145 virtual bool read(std::istream& is);
146 virtual bool write(std::ostream& os) const;
147
149 const VertexSim3Expmap* v1 =
150 static_cast<const VertexSim3Expmap*>(_vertices[1]);
151 const VertexPointXYZ* v2 = static_cast<const VertexPointXYZ*>(_vertices[0]);
152
153 Vector2 obs(_measurement);
154 _error = obs - v1->cam_map1(project(v1->estimate().map(v2->estimate())));
155 }
156
157 // virtual void linearizeOplus();
158};
159
160
162 : public BaseBinaryEdge<2, Vector2, VertexPointXYZ, VertexSim3Expmap> {
163 public:
164 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
166 virtual bool read(std::istream& is);
167 virtual bool write(std::ostream& os) const;
168
170 const VertexSim3Expmap* v1 =
171 static_cast<const VertexSim3Expmap*>(_vertices[1]);
172 const VertexPointXYZ* v2 = static_cast<const VertexPointXYZ*>(_vertices[0]);
173
174 Vector2 obs(_measurement);
175 _error = obs - v1->cam_map2(
176 project(v1->estimate().inverse().map(v2->estimate())));
177 }
178
179 // virtual void linearizeOplus();
180};
181
182} // namespace g2o
183
184#endif
Templatized BaseVertex.
Definition base_vertex.h:51
const EstimateType & estimate() const
return the current estimate of the vertex
void setEstimate(const EstimateType &et)
set the estimate for the vertex also calls updateCache()
7D edge between two Vertex7
virtual double initialEstimatePossible(const OptimizableGraph::VertexSet &, OptimizableGraph::Vertex *)
virtual void initialEstimate(const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *)
std::set< Vertex * > VertexSet
A general case Vertex for optimization.
Vertex for a tracked point in space.
Sim3 Vertex, (x,y,z,qw,qx,qy,qz) the parameterization for the increments constructed is a 7d vector (...
Vector2 cam_map2(const Vector2 &v) const
Vector2 cam_map1(const Vector2 &v) const
virtual void setToOriginImpl()
sets the node to the origin (used in the multilevel stuff)
virtual void oplusImpl(const double *update_)
VectorN< 2 > Vector2
Definition eigen_types.h:50
Vector2 project(const Vector3 &v)
Definition se3_ops.hpp:47
Vector7 log() const
Definition sim3.h:128
Vector3 map(const Vector3 &xyz) const
Definition sim3.h:126
Sim3 inverse() const
Definition sim3.h:200
#define G2O_TYPES_SIM3_API