g2o
Loading...
Searching...
No Matches
edge_se3.cpp
Go to the documentation of this file.
1// g2o - General Graph Optimization
2// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, H. Strasdat, 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.h"
28
30
31#ifdef G2O_HAVE_OPENGL
34#endif
35
36namespace g2o {
37using namespace std;
38
42
43bool EdgeSE3::read(std::istream& is) {
44 Vector7 meas;
45 internal::readVector(is, meas);
46 // normalize the quaternion to recover numerical precision lost by storing as
47 // human readable text
48 Vector4::MapType(meas.data() + 3).normalize();
50 if (is.bad()) return false;
52 return is.good() || is.eof();
53}
54
55bool EdgeSE3::write(std::ostream& os) const {
57 return writeInformationMatrix(os);
58}
59
61 VertexSE3* from = static_cast<VertexSE3*>(_vertices[0]);
62 VertexSE3* to = static_cast<VertexSE3*>(_vertices[1]);
63 Isometry3 delta =
64 _inverseMeasurement * from->estimate().inverse() * to->estimate();
66}
67
69 VertexSE3* from = static_cast<VertexSE3*>(_vertices[0]);
70 VertexSE3* to = static_cast<VertexSE3*>(_vertices[1]);
71 Isometry3 delta = from->estimate().inverse() * to->estimate();
72 setMeasurement(delta);
73 return true;
74}
75
77 // BaseBinaryEdge<6, Isometry3, VertexSE3, VertexSE3>::linearizeOplus();
78 // return;
79
80 VertexSE3* from = static_cast<VertexSE3*>(_vertices[0]);
81 VertexSE3* to = static_cast<VertexSE3*>(_vertices[1]);
82 Isometry3 E;
83 const Isometry3& Xi = from->estimate();
84 const Isometry3& Xj = to->estimate();
85 const Isometry3& Z = _measurement;
87 Xj);
88}
89
91 OptimizableGraph::Vertex* /*to_*/) {
92 VertexSE3* from = static_cast<VertexSE3*>(_vertices[0]);
93 VertexSE3* to = static_cast<VertexSE3*>(_vertices[1]);
94
95 if (from_.count(from) > 0) {
96 to->setEstimate(from->estimate() * _measurement);
97 } else
98 from->setEstimate(to->estimate() * _measurement.inverse());
99}
100
103
107 if (typeid(*element).name() != _typeName) return nullptr;
109 static_cast<WriteGnuplotAction::Parameters*>(params_);
110 if (!params->os) {
111 return nullptr;
112 }
113
114 EdgeSE3* e = static_cast<EdgeSE3*>(element);
115 VertexSE3* fromEdge = static_cast<VertexSE3*>(e->vertices()[0]);
116 VertexSE3* toEdge = static_cast<VertexSE3*>(e->vertices()[1]);
117 Vector6 fromV, toV;
118 fromV = internal::toVectorMQT(fromEdge->estimate());
119 toV = internal::toVectorMQT(toEdge->estimate());
120 for (int i = 0; i < 6; i++) {
121 *(params->os) << fromV[i] << " ";
122 }
123 for (int i = 0; i < 6; i++) {
124 *(params->os) << toV[i] << " ";
125 }
126 *(params->os) << std::endl;
127 return this;
128}
129
130#ifdef G2O_HAVE_OPENGL
131EdgeSE3DrawAction::EdgeSE3DrawAction() : DrawAction(typeid(EdgeSE3).name()) {}
132
133HyperGraphElementAction* EdgeSE3DrawAction::operator()(
134 HyperGraph::HyperGraphElement* element,
135 HyperGraphElementAction::Parameters* params_) {
136 if (typeid(*element).name() != _typeName) return nullptr;
137 refreshPropertyPtrs(params_);
138 if (!_previousParams) return this;
139
140 if (_show && !_show->value()) return this;
141
142 EdgeSE3* e = static_cast<EdgeSE3*>(element);
143 VertexSE3* fromEdge = static_cast<VertexSE3*>(e->vertices()[0]);
144 VertexSE3* toEdge = static_cast<VertexSE3*>(e->vertices()[1]);
145 if (!fromEdge || !toEdge) return this;
146 glColor3f(POSE_EDGE_COLOR);
147 glPushAttrib(GL_ENABLE_BIT);
148 glDisable(GL_LIGHTING);
149 glBegin(GL_LINES);
150 glVertex3f((float)fromEdge->estimate().translation().x(),
151 (float)fromEdge->estimate().translation().y(),
152 (float)fromEdge->estimate().translation().z());
153 glVertex3f((float)toEdge->estimate().translation().x(),
154 (float)toEdge->estimate().translation().y(),
155 (float)toEdge->estimate().translation().z());
156 glEnd();
157 glPopAttrib();
158 return this;
159}
160#endif
161
162} // namespace g2o
BaseFixedSizedEdge< D, Isometry3, VertexSE3, VertexSE3 >::template JacobianType< D, VertexXj::Dimension > & _jacobianOplusXj
BaseFixedSizedEdge< D, Isometry3, VertexSE3, VertexSE3 >::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
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
void setEstimate(const EstimateType &et)
set the estimate for the vertex also calls updateCache()
virtual HyperGraphElementAction * operator()(HyperGraph::HyperGraphElement *element, HyperGraphElementAction::Parameters *params_)
Definition edge_se3.cpp:104
Edge between two 3D pose vertices.
Definition edge_se3.h:44
void computeError()
Definition edge_se3.cpp:60
virtual void setMeasurement(const Isometry3 &m)
Definition edge_se3.h:53
void linearizeOplus()
Definition edge_se3.cpp:76
virtual bool read(std::istream &is)
read the vertex from a stream, i.e., the internal state of the vertex
Definition edge_se3.cpp:43
virtual bool write(std::ostream &os) const
write the vertex to a stream
Definition edge_se3.cpp:55
Isometry3 _inverseMeasurement
Definition edge_se3.h:86
virtual void initialEstimate(const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *to)
Definition edge_se3.cpp:90
virtual bool setMeasurementFromState()
Definition edge_se3.cpp:68
Abstract action that operates on a graph entity.
const VertexContainer & vertices() const
VertexContainer _vertices
std::set< Vertex * > VertexSet
A general case Vertex for optimization.
3D pose Vertex, represented as an Isometry3
Definition vertex_se3.h:50
Isometry3 fromVectorQT(const Vector7 &v)
Vector6 toVectorMQT(const Isometry3 &t)
void computeEdgeSE3Gradient(Isometry3 &E, Eigen::MatrixBase< Derived > const &JiConstRef, Eigen::MatrixBase< Derived > const &JjConstRef, const Isometry3 &Z, const Isometry3 &Xi, const Isometry3 &Xj, const Isometry3 &Pi, const Isometry3 &Pj)
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
Vector7 toVectorQT(const Isometry3 &t)
VectorN< 7 > Vector7
Definition eigen_types.h:54
Eigen::Transform< double, 3, Eigen::Isometry, Eigen::ColMajor > Isometry3
Definition eigen_types.h:77
VectorN< 6 > Vector6
Definition eigen_types.h:53
Definition jet.h:876
#define POSE_EDGE_COLOR