g2o
Loading...
Searching...
No Matches
types_seven_dof_expmap.cpp
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
28
29#include "g2o/core/factory.h"
30#include "g2o/stuff/macros.h"
31
32namespace g2o {
33
36
37G2O_REGISTER_TYPE(VERTEX_SIM3 : EXPMAP, VertexSim3Expmap);
38G2O_REGISTER_TYPE(EDGE_SIM3 : EXPMAP, EdgeSim3);
39G2O_REGISTER_TYPE(EDGE_PROJECT_SIM3_XYZ : EXPMAP, EdgeSim3ProjectXYZ);
40G2O_REGISTER_TYPE(EDGE_PROJECT_INVERSE_SIM3_XYZ
42
44 _marginalized = false;
45 _fix_scale = false;
46
47 _principle_point1[0] = 0;
48 _principle_point1[1] = 0;
49 _focal_length1[0] = 1;
50 _focal_length1[1] = 1;
51
52 _principle_point2[0] = 0;
53 _principle_point2[1] = 0;
54 _focal_length2[0] = 1;
55 _focal_length2[1] = 1;
56}
57
60
61bool VertexSim3Expmap::read(std::istream& is) {
62 Vector7 cam2world;
63 bool state = true;
64 state &= internal::readVector(is, cam2world);
67 setEstimate(Sim3(cam2world).inverse());
68 return state;
69}
70
71bool VertexSim3Expmap::write(std::ostream& os) const {
72 Sim3 cam2world(estimate().inverse());
73 Vector7 lv = cam2world.log();
77 return os.good();
78}
79
80bool EdgeSim3::read(std::istream& is) {
81 Vector7 v7;
83 Sim3 cam2world(v7);
84 setMeasurement(cam2world.inverse());
85 return readInformationMatrix(is);
86}
87
88bool EdgeSim3::write(std::ostream& os) const {
89 Sim3 cam2world(measurement().inverse());
90 internal::writeVector(os, cam2world.log());
91 return writeInformationMatrix(os);
92}
93
94#if G2O_SIM3_JACOBIAN
96 VertexSim3Expmap* v1 = static_cast<VertexSim3Expmap*>(_vertices[0]);
97 VertexSim3Expmap* v2 = static_cast<VertexSim3Expmap*>(_vertices[1]);
98 const Sim3 Si(v1->estimate()); // Siw
99 const Sim3 Sj(v2->estimate());
100
101 const Sim3& Sji = _measurement;
102
103 // error in Lie Algebra
104 const Eigen::Matrix<double, 7, 1> error = (Sji * Si * Sj.inverse()).log();
105 const Eigen::Vector3d phi = error.block<3, 1>(0, 0); // rotation
106 const Eigen::Vector3d tau = error.block<3, 1>(3, 0); // translation
107 const double s = error(6); // scale
108
109 const Eigen::Matrix<double, 7, 7> I7 =
110 Eigen::Matrix<double, 7, 7>::Identity();
111 const Eigen::Matrix<double, 3, 3> I3 =
112 Eigen::Matrix<double, 3, 3>::Identity();
113
114 // Jacobi Matrix of Si
115 // note: because the order of rotation and translation is different,
116 // so it is slightly different from the formula.
117 Eigen::Matrix<double, 7, 7> jacobi_i = Eigen::Matrix<double, 7, 7>::Zero();
118 jacobi_i.block<3, 3>(0, 0) = -skew(phi);
119 jacobi_i.block<3, 3>(3, 3) = -(skew(phi) + s * I3);
120 jacobi_i.block<3, 3>(3, 0) = -skew(tau);
121 jacobi_i.block<3, 1>(3, 6) = tau;
122
123 // Adjoint matrix of Sji
124 Eigen::Matrix<double, 7, 7> adj_Sji = I7;
125 adj_Sji.block<3, 3>(0, 0) = Sji.rotation().toRotationMatrix();
126 adj_Sji.block<3, 3>(3, 3) = Sji.scale() * Sji.rotation().toRotationMatrix();
127 adj_Sji.block<3, 3>(3, 0) =
128 skew(Sji.translation()) * Sji.rotation().toRotationMatrix();
129 adj_Sji.block<3, 1>(3, 6) = -Sji.translation();
130
131 _jacobianOplusXi = (I7 + 0.5 * jacobi_i) * adj_Sji;
132
133 // Jacobi Matrix of Sj
134 Eigen::Matrix<double, 7, 7> jacobi_j = Eigen::Matrix<double, 7, 7>::Zero();
135 jacobi_j.block<3, 3>(0, 0) = skew(phi);
136 jacobi_j.block<3, 3>(3, 3) = skew(phi) + s * I3;
137 jacobi_j.block<3, 3>(3, 0) = skew(tau);
138 jacobi_j.block<3, 1>(3, 6) = -tau;
139
140 _jacobianOplusXj = -(I7 + 0.5 * jacobi_j);
141}
142#endif
143
148
149bool EdgeSim3ProjectXYZ::read(std::istream& is) {
151 return readInformationMatrix(is);
152}
153
154bool EdgeSim3ProjectXYZ::write(std::ostream& os) const {
156 return writeInformationMatrix(os);
157}
158
161
162bool EdgeInverseSim3ProjectXYZ::read(std::istream& is) {
164 return readInformationMatrix(is);
165}
166
167bool EdgeInverseSim3ProjectXYZ::write(std::ostream& os) const {
169 return writeInformationMatrix(os);
170}
171
172// void EdgeSim3ProjectXYZ::linearizeOplus()
173// {
174// VertexSim3Expmap * vj = static_cast<VertexSim3Expmap *>(_vertices[1]);
175// Sim3 T = vj->estimate();
176
177// VertexPointXYZ* vi = static_cast<VertexPointXYZ*>(_vertices[0]);
178// Vector3 xyz = vi->estimate();
179// Vector3 xyz_trans = T.map(xyz);
180
181// double x = xyz_trans[0];
182// double y = xyz_trans[1];
183// double z = xyz_trans[2];
184// double z_2 = z*z;
185
186// Matrix<double,2,3,Eigen::ColMajor> tmp;
187// tmp(0,0) = _focal_length(0);
188// tmp(0,1) = 0;
189// tmp(0,2) = -x/z*_focal_length(0);
190
191// tmp(1,0) = 0;
192// tmp(1,1) = _focal_length(1);
193// tmp(1,2) = -y/z*_focal_length(1);
194
195// _jacobianOplusXi = -1./z * tmp * T.rotation().toRotationMatrix();
196
197// _jacobianOplusXj(0,0) = x*y/z_2 * _focal_length(0);
198// _jacobianOplusXj(0,1) = -(1+(x*x/z_2)) *_focal_length(0);
199// _jacobianOplusXj(0,2) = y/z *_focal_length(0);
200// _jacobianOplusXj(0,3) = -1./z *_focal_length(0);
201// _jacobianOplusXj(0,4) = 0;
202// _jacobianOplusXj(0,5) = x/z_2 *_focal_length(0);
203// _jacobianOplusXj(0,6) = 0; // scale is ignored
204
205// _jacobianOplusXj(1,0) = (1+y*y/z_2) *_focal_length(1);
206// _jacobianOplusXj(1,1) = -x*y/z_2 *_focal_length(1);
207// _jacobianOplusXj(1,2) = -x/z *_focal_length(1);
208// _jacobianOplusXj(1,3) = 0;
209// _jacobianOplusXj(1,4) = -1./z *_focal_length(1);
210// _jacobianOplusXj(1,5) = y/z_2 *_focal_length(1);
211// _jacobianOplusXj(1,6) = 0; // scale is ignored
212// }
213
214} // namespace g2o
BaseFixedSizedEdge< D, Sim3, VertexSim3Expmap, VertexSim3Expmap >::template JacobianType< D, VertexXj::Dimension > & _jacobianOplusXj
BaseFixedSizedEdge< D, Sim3, VertexSim3Expmap, VertexSim3Expmap >::template JacobianType< D, VertexXi::Dimension > & _jacobianOplusXi
bool writeInformationMatrix(std::ostream &os) const
write the upper trinagular part of the information matrix into the stream
Definition base_edge.h:165
bool readInformationMatrix(std::istream &is)
Definition base_edge.h:173
EIGEN_STRONG_INLINE const Measurement & measurement() const
accessor functions for the measurement represented by the edge
Definition base_edge.h:119
virtual void setMeasurement(const Measurement &m)
Definition base_edge.h:122
const ErrorVector & error() const
Definition base_edge.h:103
Measurement _measurement
the measurement of the edge
Definition base_edge.h:146
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()
virtual bool write(std::ostream &os) const
write the vertex to a stream
virtual bool read(std::istream &is)
read the vertex from a stream, i.e., the internal state of the vertex
EIGEN_MAKE_ALIGNED_OPERATOR_NEW EdgeInverseSim3ProjectXYZ()
EIGEN_MAKE_ALIGNED_OPERATOR_NEW EdgeSim3ProjectXYZ()
virtual bool write(std::ostream &os) const
write the vertex to a stream
virtual bool read(std::istream &is)
read the vertex from a stream, i.e., the internal state of the vertex
7D edge between two Vertex7
EIGEN_MAKE_ALIGNED_OPERATOR_NEW EdgeSim3()
virtual bool read(std::istream &is)
read the vertex from a stream, i.e., the internal state of the vertex
virtual bool write(std::ostream &os) const
write the vertex to a stream
VertexContainer _vertices
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 (...
virtual bool read(std::istream &is)
read the vertex from a stream, i.e., the internal state of the vertex
virtual bool write(std::ostream &os) const
write the vertex to a stream
#define G2O_REGISTER_TYPE(name, classname)
Definition factory.h:148
#define G2O_REGISTER_TYPE_GROUP(typeGroupName)
Definition factory.h:156
#define G2O_USE_TYPE_GROUP(typeGroupName)
Definition factory.h:159
bool writeVector(std::ostream &os, const Eigen::DenseBase< Derived > &b)
Definition io_helper.h:36
bool readVector(std::istream &is, Eigen::DenseBase< Derived > &b)
Definition io_helper.h:42
VectorN< 7 > Vector7
Definition eigen_types.h:54
G2O_TYPES_SLAM3D_API Matrix3 skew(const Vector3 &v)
VectorN< 2 > Vector2
Definition eigen_types.h:50
Vector7 log() const
Definition sim3.h:128
const Quaternion & rotation() const
Definition sim3.h:249
Sim3 inverse() const
Definition sim3.h:200
const Vector3 & translation() const
Definition sim3.h:245
const double & scale() const
Definition sim3.h:253