g2o
Loading...
Searching...
No Matches
edge_sba_scale.cpp
Go to the documentation of this file.
1// g2o - General Graph Optimization
2// Copyright (C) 2011 Kurt Konolige
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_sba_scale.h"
28
29namespace g2o {
30
31// point to camera projection, stereo
34
35bool EdgeSBAScale::read(std::istream& is) {
36 double meas;
37 is >> meas;
38 setMeasurement(meas);
39 information().setIdentity();
40 is >> information()(0, 0);
41 return true;
42}
43
44bool EdgeSBAScale::write(std::ostream& os) const {
45 os << measurement() << " " << information()(0, 0);
46 return os.good();
47}
48
50 OptimizableGraph::Vertex* /*to_*/) {
51 VertexCam* v1 = dynamic_cast<VertexCam*>(_vertices[0]);
52 VertexCam* v2 = dynamic_cast<VertexCam*>(_vertices[1]);
53 // compute the translation vector of v1 w.r.t v2
54 if (from_.count(v1) == 1) {
55 SE3Quat delta = (v1->estimate().inverse() * v2->estimate());
56 double norm = delta.translation().norm();
57 double alpha = _measurement / norm;
58 delta.setTranslation(delta.translation() * alpha);
59 v2->setEstimate(v1->estimate() * delta);
60 } else {
61 SE3Quat delta = (v2->estimate().inverse() * v1->estimate());
62 double norm = delta.translation().norm();
63 double alpha = _measurement / norm;
64 delta.setTranslation(delta.translation() * alpha);
65 v1->setEstimate(v2->estimate() * delta);
66 }
67}
68
70 const VertexCam* v1 = dynamic_cast<const VertexCam*>(_vertices[0]);
71 const VertexCam* v2 = dynamic_cast<const VertexCam*>(_vertices[1]);
72 Vector3 dt = v2->estimate().translation() - v1->estimate().translation();
73 _error[0] = _measurement - dt.norm();
74}
75
76} // namespace g2o
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
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
virtual bool read(std::istream &is)
read the vertex from a stream, i.e., the internal state of the vertex
virtual bool write(std::ostream &os) const
write the vertex to a stream
virtual void initialEstimate(const OptimizableGraph::VertexSet &from_, OptimizableGraph::Vertex *to_)
virtual void setMeasurement(const double &m)
EIGEN_MAKE_ALIGNED_OPERATOR_NEW EdgeSBAScale()
VertexContainer _vertices
std::set< Vertex * > VertexSet
A general case Vertex for optimization.
const Vector3 & translation() const
Definition se3quat.h:89
SE3Quat inverse() const
Definition se3quat.h:114
void setTranslation(const Vector3 &t_)
Definition se3quat.h:91
SBACam Vertex, (x,y,z,qw,qx,qy,qz) the parameterization for the increments constructed is a 6d vector...
Definition vertex_cam.h:43
virtual void setEstimate(const SBACam &cam)
Definition vertex_cam.h:53
VectorN< 3 > Vector3
Definition eigen_types.h:51