g2o
Loading...
Searching...
No Matches
edge_se3_pointxyz.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
27#include "edge_se3_pointxyz.h"
28
30
31#ifdef G2O_HAVE_OPENGL
33#endif
34
35#include <cassert>
36
37#ifdef G2O_HAVE_OPENGL
40#endif
41
42namespace g2o {
43using namespace std;
44
45// point to camera projection, monocular
48 information().setIdentity();
49 J.fill(0);
50 J.block<3, 3>(0, 0) = -Matrix3::Identity();
51 cache = 0;
52 offsetParam = 0;
55}
56
58 ParameterVector pv(1);
59 pv[0] = offsetParam;
61 "CACHE_SE3_OFFSET", pv);
62 return cache != 0;
63}
64
65bool EdgeSE3PointXYZ::read(std::istream& is) {
66 readParamIds(is);
67 Vector3 meas;
68 internal::readVector(is, meas);
69 setMeasurement(meas);
71 return is.good() || is.eof();
72}
73
74bool EdgeSE3PointXYZ::write(std::ostream& os) const {
75 bool state = writeParamIds(os);
76 state &= internal::writeVector(os, measurement());
77 state &= writeInformationMatrix(os);
78 return state;
79}
80
82 // from cam to point (track)
83 // VertexSE3 *cam = static_cast<VertexSE3*>(_vertices[0]);
84 VertexPointXYZ* point = static_cast<VertexPointXYZ*>(_vertices[1]);
85
86 Vector3 perr = cache->w2n() * point->estimate();
87
88 // error, which is backwards from the normal observed - calculated
89 // _measurement is the measured projection
90 _error = perr - _measurement;
91 // std::cout << _error << std::endl << std::endl;
92}
93
95 // VertexSE3 *cam = static_cast<VertexSE3 *>(_vertices[0]);
96 VertexPointXYZ* vp = static_cast<VertexPointXYZ*>(_vertices[1]);
97
98 Vector3 Zcam = cache->w2l() * vp->estimate();
99
100 // J(0,3) = -0.0;
101 J(0, 4) = -2 * Zcam(2);
102 J(0, 5) = 2 * Zcam(1);
103
104 J(1, 3) = 2 * Zcam(2);
105 // J(1,4) = -0.0;
106 J(1, 5) = -2 * Zcam(0);
107
108 J(2, 3) = -2 * Zcam(1);
109 J(2, 4) = 2 * Zcam(0);
110 // J(2,5) = -0.0;
111
112 J.block<3, 3>(0, 6) = cache->w2l().rotation();
113
114 Eigen::Matrix<double, 3, 9, Eigen::ColMajor> Jhom =
115 offsetParam->inverseOffset().rotation() * J;
116
117 _jacobianOplusXi = Jhom.block<3, 6>(0, 0);
118 _jacobianOplusXj = Jhom.block<3, 3>(0, 6);
119}
120
122 // VertexSE3 *cam = static_cast<VertexSE3*>(_vertices[0]);
123 VertexPointXYZ* point = static_cast<VertexPointXYZ*>(_vertices[1]);
124
125 // calculate the projection
126 const Vector3& pt = point->estimate();
127
128 Vector3 perr = cache->w2n() * pt;
129 _measurement = perr;
130 return true;
131}
132
135 (void)from;
136 (void)to;
137 assert(from.size() == 1 && from.count(_vertices[0]) == 1 &&
138 "Can not initialize VertexDepthCam position by VertexTrackXYZ");
139
140 VertexSE3* cam = dynamic_cast<VertexSE3*>(_vertices[0]);
141 VertexPointXYZ* point = dynamic_cast<VertexPointXYZ*>(_vertices[1]);
143 point->setEstimate(cam->estimate() * (offsetParam->offset() * p));
144}
145
146#ifdef G2O_HAVE_OPENGL
147EdgeSE3PointXYZDrawAction::EdgeSE3PointXYZDrawAction()
148 : DrawAction(typeid(EdgeSE3PointXYZ).name()) {}
149
150HyperGraphElementAction* EdgeSE3PointXYZDrawAction::operator()(
151 HyperGraph::HyperGraphElement* element,
152 HyperGraphElementAction::Parameters* params_) {
153 if (typeid(*element).name() != _typeName) return nullptr;
154 refreshPropertyPtrs(params_);
155 if (!_previousParams) return this;
156
157 if (_show && !_show->value()) return this;
158
159 EdgeSE3PointXYZ* e = static_cast<EdgeSE3PointXYZ*>(element);
160 VertexSE3* fromEdge = static_cast<VertexSE3*>(e->vertex(0));
161 VertexPointXYZ* toEdge = static_cast<VertexPointXYZ*>(e->vertex(1));
162 if (!fromEdge || !toEdge) return this;
163 Isometry3 fromTransform =
164 fromEdge->estimate() * e->offsetParameter()->offset();
165 glColor3f(LANDMARK_EDGE_COLOR);
166 glPushAttrib(GL_ENABLE_BIT);
167 glDisable(GL_LIGHTING);
168 glBegin(GL_LINES);
169 glVertex3f((float)fromTransform.translation().x(),
170 (float)fromTransform.translation().y(),
171 (float)fromTransform.translation().z());
172 glVertex3f((float)toEdge->estimate().x(), (float)toEdge->estimate().y(),
173 (float)toEdge->estimate().z());
174 glEnd();
175 glPopAttrib();
176 return this;
177}
178#endif
179
180} // 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 Isometry3 & w2n() const
const Isometry3 & w2l() const
g2o edge from a track to a point node
ParameterSE3Offset * offsetParam
virtual void initialEstimate(const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *to)
virtual bool write(std::ostream &os) const
write the vertex to a stream
virtual bool setMeasurementFromState()
virtual bool read(std::istream &is)
read the vertex from a stream, i.e., the internal state of the vertex
CacheSE3Offset * cache
Eigen::Matrix< double, 3, 9, Eigen::ColMajor > J
virtual void linearizeOplus()
virtual void setMeasurement(const Vector3 &m)
EIGEN_MAKE_ALIGNED_OPERATOR_NEW EdgeSE3PointXYZ()
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 Isometry3 & inverseOffset() const
rotation of the inverse offset as 3x3 rotation matrix
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
Eigen::Transform< double, 3, Eigen::Isometry, Eigen::ColMajor > Isometry3
Definition eigen_types.h:77
std::vector< Parameter * > ParameterVector
Definition parameter.h:54
Definition jet.h:876
#define LANDMARK_EDGE_COLOR