g2o
Loading...
Searching...
No Matches
edge_project_xyz2uv.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
27#include "edge_project_xyz2uv.h"
28
29namespace g2o {
30
37
38bool EdgeProjectXYZ2UV::read(std::istream& is) {
39 readParamIds(is);
41 return readInformationMatrix(is);
42}
43
44bool EdgeProjectXYZ2UV::write(std::ostream& os) const {
45 writeParamIds(os);
47 return writeInformationMatrix(os);
48}
49
51 const VertexSE3Expmap* v1 = static_cast<const VertexSE3Expmap*>(_vertices[1]);
52 const VertexPointXYZ* v2 = static_cast<const VertexPointXYZ*>(_vertices[0]);
53 const CameraParameters* cam =
54 static_cast<const CameraParameters*>(parameter(0));
55 _error = measurement() - cam->cam_map(v1->estimate().map(v2->estimate()));
56}
57
59 VertexSE3Expmap* vj = static_cast<VertexSE3Expmap*>(_vertices[1]);
60 SE3Quat T(vj->estimate());
61 VertexPointXYZ* vi = static_cast<VertexPointXYZ*>(_vertices[0]);
62 Vector3 xyz = vi->estimate();
63 Vector3 xyz_trans = T.map(xyz);
64
65 double x = xyz_trans[0];
66 double y = xyz_trans[1];
67 double z = xyz_trans[2];
68 double z_2 = z * z;
69
70 const CameraParameters* cam =
71 static_cast<const CameraParameters*>(parameter(0));
72
73 Eigen::Matrix<double, 2, 3, Eigen::ColMajor> tmp;
74 tmp(0, 0) = cam->focal_length;
75 tmp(0, 1) = 0;
76 tmp(0, 2) = -x / z * cam->focal_length;
77
78 tmp(1, 0) = 0;
79 tmp(1, 1) = cam->focal_length;
80 tmp(1, 2) = -y / z * cam->focal_length;
81
82 _jacobianOplusXi = -1. / z * tmp * T.rotation().toRotationMatrix();
83
84 _jacobianOplusXj(0, 0) = x * y / z_2 * cam->focal_length;
85 _jacobianOplusXj(0, 1) = -(1 + (x * x / z_2)) * cam->focal_length;
86 _jacobianOplusXj(0, 2) = y / z * cam->focal_length;
87 _jacobianOplusXj(0, 3) = -1. / z * cam->focal_length;
88 _jacobianOplusXj(0, 4) = 0;
89 _jacobianOplusXj(0, 5) = x / z_2 * cam->focal_length;
90
91 _jacobianOplusXj(1, 0) = (1 + y * y / z_2) * cam->focal_length;
92 _jacobianOplusXj(1, 1) = -x * y / z_2 * cam->focal_length;
93 _jacobianOplusXj(1, 2) = -x / z * cam->focal_length;
94 _jacobianOplusXj(1, 3) = 0;
95 _jacobianOplusXj(1, 4) = -1. / z * cam->focal_length;
96 _jacobianOplusXj(1, 5) = y / z_2 * cam->focal_length;
97}
98
99} // namespace g2o
BaseFixedSizedEdge< D, Vector2, VertexPointXYZ, VertexSE3Expmap >::template JacobianType< D, VertexXj::Dimension > & _jacobianOplusXj
BaseFixedSizedEdge< D, Vector2, 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
bool readParamIds(std::istream &is)
reads the param IDs from the stream
Definition base_edge.h:187
EIGEN_STRONG_INLINE const Measurement & measurement() const
accessor functions for the measurement represented by the edge
Definition base_edge.h:119
bool writeParamIds(std::ostream &os) const
write the param IDs that are potentially used by the edge
Definition base_edge.h:182
Measurement _measurement
the measurement of the edge
Definition base_edge.h:146
ErrorVector _error
Definition base_edge.h:149
const EstimateType & estimate() const
return the current estimate of the vertex
Vector2 cam_map(const Vector3 &trans_xyz) const
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
VertexContainer _vertices
const Parameter * parameter(int argNo) const
bool installParameter(ParameterType *&p, size_t argNo, int paramId=-1)
void resizeParameters(size_t newSize)
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
VectorN< 2 > Vector2
Definition eigen_types.h:50