g2o
Loading...
Searching...
No Matches
edge_se3_pointxyz_depth.cpp
Go to the documentation of this file.
1// g2o - General Graph Optimization
2// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard
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 <cassert>
30
31namespace g2o {
32
33// point to camera projection, monocular
35 : BaseBinaryEdge<3, Vector3, VertexSE3, VertexPointXYZ>(), cache(nullptr) {
38 information().setIdentity();
39 information()(2, 2) = 100;
40 J.fill(0);
41 J.block<3, 3>(0, 0) = -Matrix3::Identity();
42}
43
45 ParameterVector pv(1);
46 pv[0] = params;
48 pv);
49 return cache != 0;
50}
51
52bool EdgeSE3PointXYZDepth::read(std::istream& is) {
53 readParamIds(is);
54 internal::readVector(is, _measurement); // measured keypoint
55 return readInformationMatrix(is);
56}
57
58bool EdgeSE3PointXYZDepth::write(std::ostream& os) const {
59 writeParamIds(os);
61 return writeInformationMatrix(os);
62}
63
65 // from cam to point (track)
66 // VertexSE3 *cam = static_cast<VertexSE3*>(_vertices[0]);
67 VertexPointXYZ* point = static_cast<VertexPointXYZ*>(_vertices[1]);
68
69 Vector3 p = cache->w2i() * point->estimate();
70 Vector3 perr;
71 perr.head<2>() = p.head<2>() / p(2);
72 perr(2) = p(2);
73
74 // error, which is backwards from the normal observed - calculated
75 // _measurement is the measured projection
76 _error = perr - _measurement;
77}
78
80 // VertexSE3 *cam = static_cast<VertexSE3 *>(_vertices[0]);
81 VertexPointXYZ* vp = static_cast<VertexPointXYZ*>(_vertices[1]);
82
83 const Vector3& pt = vp->estimate();
84
85 Vector3 Zcam = cache->w2l() * pt;
86
87 // J(0,3) = -0.0;
88 J(0, 4) = -2 * Zcam(2);
89 J(0, 5) = 2 * Zcam(1);
90
91 J(1, 3) = 2 * Zcam(2);
92 // J(1,4) = -0.0;
93 J(1, 5) = -2 * Zcam(0);
94
95 J(2, 3) = -2 * Zcam(1);
96 J(2, 4) = 2 * Zcam(0);
97 // J(2,5) = -0.0;
98
99 J.block<3, 3>(0, 6) = cache->w2l().rotation();
100
101 Eigen::Matrix<double, 3, 9, Eigen::ColMajor> Jprime =
103 Vector3 Zprime = cache->w2i() * pt;
104
105 Eigen::Matrix<double, 3, 9, Eigen::ColMajor> Jhom;
106 Jhom.block<2, 9>(0, 0) = 1 / (Zprime(2) * Zprime(2)) *
107 (Jprime.block<2, 9>(0, 0) * Zprime(2) -
108 Zprime.head<2>() * Jprime.block<1, 9>(2, 0));
109 Jhom.block<1, 9>(2, 0) = Jprime.block<1, 9>(2, 0);
110
111 _jacobianOplusXi = Jhom.block<3, 6>(0, 0);
112 _jacobianOplusXj = Jhom.block<3, 3>(0, 6);
113}
114
116 // VertexSE3 *cam = static_cast<VertexSE3*>(_vertices[0]);
117 VertexPointXYZ* point = static_cast<VertexPointXYZ*>(_vertices[1]);
118
119 // calculate the projection
120 const Vector3& pt = point->estimate();
121
122 Vector3 p = cache->w2i() * pt;
123 Vector3 perr;
124 perr.head<2>() = p.head<2>() / p(2);
125 perr(2) = p(2);
126 _measurement = perr;
127 return true;
128}
129
131 const OptimizableGraph::VertexSet& from,
132 OptimizableGraph::Vertex* /*to_*/) {
133 (void)from;
134 assert(from.size() == 1 && from.count(_vertices[0]) == 1 &&
135 "Can not initialize VertexDepthCam position by VertexTrackXYZ");
136
137 VertexSE3* cam = dynamic_cast<VertexSE3*>(_vertices[0]);
138 VertexPointXYZ* point = dynamic_cast<VertexPointXYZ*>(_vertices[1]);
139 const Eigen::Matrix<double, 3, 3, Eigen::ColMajor>& invKcam =
140 params->invKcam();
141 Vector3 p;
142 p(2) = _measurement(2);
143 p.head<2>() = _measurement.head<2>() * p(2);
144 p = invKcam * p;
145 point->setEstimate(cam->estimate() * (params->offset() * p));
146}
147
148} // namespace g2o
BaseFixedSizedEdge< D, Vector3, VertexSE3, VertexPointXYZ >::template JacobianType< D, VertexXj::Dimension > & _jacobianOplusXj
BaseFixedSizedEdge< D, Vector3, VertexSE3, VertexPointXYZ >::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
EIGEN_STRONG_INLINE const InformationType & information() const
information matrix of the constraint
Definition base_edge.h:107
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
void setEstimate(const EstimateType &et)
set the estimate for the vertex also calls updateCache()
const Affine3 & w2i() const
return the world to image transform
const Isometry3 & w2l() const
Eigen::Matrix< double, 3, 9, Eigen::ColMajor > J
virtual void initialEstimate(const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *to)
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 EdgeSE3PointXYZDepth()
virtual bool write(std::ostream &os) const
write the vertex to a stream
VertexContainer _vertices
std::set< Vertex * > VertexSet
bool installParameter(ParameterType *&p, size_t argNo, int paramId=-1)
void resizeParameters(size_t newSize)
void resolveCache(CacheType *&cache, OptimizableGraph::Vertex *, const std::string &_type, const ParameterVector &parameters)
Definition cache.h:125
A general case Vertex for optimization.
const Matrix3 & invKcam() const
const Matrix3 & Kcam_inverseOffsetR() const
const Isometry3 & offset() const
rotation of the offset as 3x3 rotation matrix
Vertex for a tracked point in space.
3D pose Vertex, represented as an Isometry3
Definition vertex_se3.h:50
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
std::vector< Parameter * > ParameterVector
Definition parameter.h:54