g2o
Loading...
Searching...
No Matches
edge_project_stereo_xyz_onlypose.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
35
36bool EdgeStereoSE3ProjectXYZOnlyPose::write(std::ostream& os) const {
38 return writeInformationMatrix(os);
39}
40
42 VertexSE3Expmap* vi = static_cast<VertexSE3Expmap*>(_vertices[0]);
43 Vector3 xyz_trans = vi->estimate().map(Xw);
44
45 double x = xyz_trans[0];
46 double y = xyz_trans[1];
47 double invz = 1.0 / xyz_trans[2];
48 double invz_2 = invz * invz;
49
50 _jacobianOplusXi(0, 0) = x * y * invz_2 * fx;
51 _jacobianOplusXi(0, 1) = -(1 + (x * x * invz_2)) * fx;
52 _jacobianOplusXi(0, 2) = y * invz * fx;
53 _jacobianOplusXi(0, 3) = -invz * fx;
54 _jacobianOplusXi(0, 4) = 0;
55 _jacobianOplusXi(0, 5) = x * invz_2 * fx;
56
57 _jacobianOplusXi(1, 0) = (1 + y * y * invz_2) * fy;
58 _jacobianOplusXi(1, 1) = -x * y * invz_2 * fy;
59 _jacobianOplusXi(1, 2) = -x * invz * fy;
60 _jacobianOplusXi(1, 3) = 0;
61 _jacobianOplusXi(1, 4) = -invz * fy;
62 _jacobianOplusXi(1, 5) = y * invz_2 * fy;
63
64 _jacobianOplusXi(2, 0) = _jacobianOplusXi(0, 0) - bf * y * invz_2;
65 _jacobianOplusXi(2, 1) = _jacobianOplusXi(0, 1) + bf * x * invz_2;
68 _jacobianOplusXi(2, 4) = 0;
69 _jacobianOplusXi(2, 5) = _jacobianOplusXi(0, 5) - bf * invz_2;
70}
71
73 const VertexSE3Expmap* v1 = static_cast<const VertexSE3Expmap*>(_vertices[0]);
75 _error = obs - cam_project(v1->estimate().map(Xw));
76}
77
79 const VertexSE3Expmap* v1 = static_cast<const VertexSE3Expmap*>(_vertices[0]);
80 return (v1->estimate().map(Xw))(2) > 0;
81}
82
84 const Vector3& trans_xyz) const {
85 const float invz = 1.0f / trans_xyz[2];
86 Vector3 res;
87 res[0] = trans_xyz[0] * invz * fx + cx;
88 res[1] = trans_xyz[1] * invz * fy + cy;
89 res[2] = res[0] - bf * invz;
90 return res;
91}
92
93} // namespace g2o
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
ErrorVector _error
Definition base_edge.h:149
BaseFixedSizedEdge< D, Vector3, VertexSE3Expmap >::template JacobianType< D, VertexXi::Dimension > & _jacobianOplusXi
const EstimateType & estimate() const
return the current estimate of the vertex
bool write(std::ostream &os) const
write the vertex to a stream
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
VertexContainer _vertices
Vector3 map(const Vector3 &xyz) const
Definition se3quat.h:200
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