g2o
Loading...
Searching...
No Matches
edge_project_stereo_xyz.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
29namespace g2o {
30
33
35 const float& bf) const {
36 const double invz = 1.0f / trans_xyz[2];
37 Vector3 res;
38 res[0] = trans_xyz[0] * invz * fx + cx;
39 res[1] = trans_xyz[1] * invz * fy + cy;
40 res[2] = res[0] - bf * invz;
41 return res;
42}
43
44bool EdgeStereoSE3ProjectXYZ::read(std::istream& is) {
46 return readInformationMatrix(is);
47}
48
49bool EdgeStereoSE3ProjectXYZ::write(std::ostream& os) const {
51 return writeInformationMatrix(os);
52}
53
55 VertexSE3Expmap* vj = static_cast<VertexSE3Expmap*>(_vertices[1]);
56 SE3Quat T(vj->estimate());
57 VertexPointXYZ* vi = static_cast<VertexPointXYZ*>(_vertices[0]);
58 Vector3 xyz = vi->estimate();
59 Vector3 xyz_trans = T.map(xyz);
60
61 const Matrix3 R = T.rotation().toRotationMatrix();
62
63 double x = xyz_trans[0];
64 double y = xyz_trans[1];
65 double z = xyz_trans[2];
66 double z_2 = z * z;
67
68 _jacobianOplusXi(0, 0) = -fx * R(0, 0) / z + fx * x * R(2, 0) / z_2;
69 _jacobianOplusXi(0, 1) = -fx * R(0, 1) / z + fx * x * R(2, 1) / z_2;
70 _jacobianOplusXi(0, 2) = -fx * R(0, 2) / z + fx * x * R(2, 2) / z_2;
71
72 _jacobianOplusXi(1, 0) = -fy * R(1, 0) / z + fy * y * R(2, 0) / z_2;
73 _jacobianOplusXi(1, 1) = -fy * R(1, 1) / z + fy * y * R(2, 1) / z_2;
74 _jacobianOplusXi(1, 2) = -fy * R(1, 2) / z + fy * y * R(2, 2) / z_2;
75
76 _jacobianOplusXi(2, 0) = _jacobianOplusXi(0, 0) - bf * R(2, 0) / z_2;
77 _jacobianOplusXi(2, 1) = _jacobianOplusXi(0, 1) - bf * R(2, 1) / z_2;
78 _jacobianOplusXi(2, 2) = _jacobianOplusXi(0, 2) - bf * R(2, 2) / z_2;
79
80 _jacobianOplusXj(0, 0) = x * y / z_2 * fx;
81 _jacobianOplusXj(0, 1) = -(1 + (x * x / z_2)) * fx;
82 _jacobianOplusXj(0, 2) = y / z * fx;
83 _jacobianOplusXj(0, 3) = -1. / z * fx;
84 _jacobianOplusXj(0, 4) = 0;
85 _jacobianOplusXj(0, 5) = x / z_2 * fx;
86
87 _jacobianOplusXj(1, 0) = (1 + y * y / z_2) * fy;
88 _jacobianOplusXj(1, 1) = -x * y / z_2 * fy;
89 _jacobianOplusXj(1, 2) = -x / z * fy;
90 _jacobianOplusXj(1, 3) = 0;
91 _jacobianOplusXj(1, 4) = -1. / z * fy;
92 _jacobianOplusXj(1, 5) = y / z_2 * fy;
93
94 _jacobianOplusXj(2, 0) = _jacobianOplusXj(0, 0) - bf * y / z_2;
95 _jacobianOplusXj(2, 1) = _jacobianOplusXj(0, 1) + bf * x / z_2;
98 _jacobianOplusXj(2, 4) = 0;
99 _jacobianOplusXj(2, 5) = _jacobianOplusXj(0, 5) - bf / z_2;
100}
101
102} // namespace g2o
BaseFixedSizedEdge< D, Vector3, VertexPointXYZ, VertexSE3Expmap >::template JacobianType< D, VertexXj::Dimension > & _jacobianOplusXj
BaseFixedSizedEdge< D, Vector3, VertexPointXYZ, VertexSE3Expmap >::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
Measurement _measurement
the measurement of the edge
Definition base_edge.h:146
const EstimateType & estimate() const
return the current estimate of the vertex
EIGEN_MAKE_ALIGNED_OPERATOR_NEW EdgeStereoSE3ProjectXYZ()
bool read(std::istream &is)
read the vertex from a stream, i.e., the internal state of the vertex
Vector3 cam_project(const Vector3 &trans_xyz, const float &bf) const
bool write(std::ostream &os) const
write the vertex to a stream
VertexContainer _vertices
const Quaternion & rotation() const
Definition se3quat.h:93
Vector3 map(const Vector3 &xyz) const
Definition se3quat.h:200
Vertex for a tracked point in space.
SE3 Vertex parameterized internally with a transformation matrix and externally with its exponential ...
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< 3 > Vector3
Definition eigen_types.h:51
MatrixN< 3 > Matrix3
Definition eigen_types.h:72