g2o
Loading...
Searching...
No Matches
edge_se2.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_se2.h"
28
29#ifdef G2O_HAVE_OPENGL
32#endif
33
34namespace g2o {
35
37
38bool EdgeSE2::read(std::istream& is) {
39 Vector3 p;
44 return is.good() || is.eof();
45}
46
47bool EdgeSE2::write(std::ostream& os) const {
48 internal::writeVector(os, measurement().toVector());
49 return writeInformationMatrix(os);
50}
51
53 OptimizableGraph::Vertex* /* to */) {
54 VertexSE2* fromEdge = static_cast<VertexSE2*>(_vertices[0]);
55 VertexSE2* toEdge = static_cast<VertexSE2*>(_vertices[1]);
56 if (from.count(fromEdge) > 0)
57 toEdge->setEstimate(fromEdge->estimate() * _measurement);
58 else
59 fromEdge->setEstimate(toEdge->estimate() * _inverseMeasurement);
60}
61
62#ifndef NUMERIC_JACOBIAN_TWO_D_TYPES
64 const VertexSE2* vi = static_cast<const VertexSE2*>(_vertices[0]);
65 const VertexSE2* vj = static_cast<const VertexSE2*>(_vertices[1]);
66 double thetai = vi->estimate().rotation().angle();
67
68 Vector2 dt = vj->estimate().translation() - vi->estimate().translation();
69 double si = std::sin(thetai), ci = std::cos(thetai);
70
71 _jacobianOplusXi << -ci, -si, -si * dt.x() + ci * dt.y(), si, -ci,
72 -ci * dt.x() - si * dt.y(), 0, 0, -1;
73
74 _jacobianOplusXj << ci, si, 0, -si, ci, 0, 0, 0, 1;
75
76 const SE2& rmean = _inverseMeasurement;
77 Matrix3 z;
78 z.block<2, 2>(0, 0) = rmean.rotation().toRotationMatrix();
79 z.col(2) << cst(0.), cst(0.), cst(1.);
80 z.row(2).head<2>() << cst(0.), cst(0.);
83}
84#endif
85
88
92 if (typeid(*element).name() != _typeName) return nullptr;
94 static_cast<WriteGnuplotAction::Parameters*>(params_);
95 if (!params->os) {
96 return nullptr;
97 }
98
99 EdgeSE2* e = static_cast<EdgeSE2*>(element);
100 VertexSE2* fromEdge = static_cast<VertexSE2*>(e->vertex(0));
101 VertexSE2* toEdge = static_cast<VertexSE2*>(e->vertex(1));
102 *(params->os) << fromEdge->estimate().translation().x() << " "
103 << fromEdge->estimate().translation().y() << " "
104 << fromEdge->estimate().rotation().angle() << std::endl;
105 *(params->os) << toEdge->estimate().translation().x() << " "
106 << toEdge->estimate().translation().y() << " "
107 << toEdge->estimate().rotation().angle() << std::endl;
108 *(params->os) << std::endl;
109 return this;
110}
111
112#ifdef G2O_HAVE_OPENGL
113EdgeSE2DrawAction::EdgeSE2DrawAction()
114 : DrawAction(typeid(EdgeSE2).name()),
115 _triangleX(nullptr),
116 _triangleY(nullptr) {}
117
118bool EdgeSE2DrawAction::refreshPropertyPtrs(
119 HyperGraphElementAction::Parameters* params_) {
120 if (!DrawAction::refreshPropertyPtrs(params_)) return false;
121 if (_previousParams) {
122 _triangleX = _previousParams->makeProperty<FloatProperty>(
123 _typeName + "::GHOST_TRIANGLE_X", .2f);
124 _triangleY = _previousParams->makeProperty<FloatProperty>(
125 _typeName + "::GHOST_TRIANGLE_Y", .05f);
126 } else {
127 _triangleX = 0;
128 _triangleY = 0;
129 }
130 return true;
131}
132
133HyperGraphElementAction* EdgeSE2DrawAction::operator()(
134 HyperGraph::HyperGraphElement* element,
135 HyperGraphElementAction::Parameters* params_) {
136 if (typeid(*element).name() != _typeName) return nullptr;
137
138 refreshPropertyPtrs(params_);
139 if (!_previousParams) return this;
140
141 if (_show && !_show->value()) return this;
142
143 EdgeSE2* e = static_cast<EdgeSE2*>(element);
144 VertexSE2* from = static_cast<VertexSE2*>(e->vertex(0));
145 VertexSE2* to = static_cast<VertexSE2*>(e->vertex(1));
146 if (!from && !to) return this;
147 SE2 fromTransform;
148 SE2 toTransform;
149 glPushAttrib(GL_ENABLE_BIT | GL_LIGHTING | GL_COLOR);
150 glDisable(GL_LIGHTING);
151 if (!from) {
152 glColor3f(POSE_EDGE_GHOST_COLOR);
153 toTransform = to->estimate();
154 fromTransform = to->estimate() * e->measurement().inverse();
155 // DRAW THE FROM EDGE AS AN ARROW
156 glPushMatrix();
157 glTranslatef((float)fromTransform.translation().x(),
158 (float)fromTransform.translation().y(), 0.f);
159 glRotatef((float)RAD2DEG(fromTransform.rotation().angle()), 0.f, 0.f, 1.f);
160 opengl::drawArrow2D((float)_triangleX->value(), (float)_triangleY->value(),
161 (float)_triangleX->value() * .3f);
162 glPopMatrix();
163 } else if (!to) {
164 glColor3f(POSE_EDGE_GHOST_COLOR);
165 fromTransform = from->estimate();
166 toTransform = from->estimate() * e->measurement();
167 // DRAW THE TO EDGE AS AN ARROW
168 glPushMatrix();
169 glTranslatef(toTransform.translation().x(), toTransform.translation().y(),
170 0.f);
171 glRotatef((float)RAD2DEG(toTransform.rotation().angle()), 0.f, 0.f, 1.f);
172 opengl::drawArrow2D((float)_triangleX->value(), (float)_triangleY->value(),
173 (float)_triangleX->value() * .3f);
174 glPopMatrix();
175 } else {
176 glColor3f(POSE_EDGE_COLOR);
177 fromTransform = from->estimate();
178 toTransform = to->estimate();
179 }
180 glBegin(GL_LINES);
181 glVertex3f((float)fromTransform.translation().x(),
182 (float)fromTransform.translation().y(), 0.f);
183 glVertex3f((float)toTransform.translation().x(),
184 (float)toTransform.translation().y(), 0.f);
185 glEnd();
186 glPopAttrib();
187 return this;
188}
189#endif
190
191} // namespace g2o
BaseFixedSizedEdge< D, SE2, VertexSE2, VertexSE2 >::template JacobianType< D, VertexXj::Dimension > & _jacobianOplusXj
BaseFixedSizedEdge< D, SE2, VertexSE2, VertexSE2 >::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
Measurement _measurement
the measurement of the edge
Definition base_edge.h:146
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 bool refreshPropertyPtrs(HyperGraphElementAction::Parameters *params_)
virtual HyperGraphElementAction * operator()(HyperGraph::HyperGraphElement *element, HyperGraphElementAction::Parameters *params_)
Definition edge_se2.cpp:89
2D edge between two Vertex2
Definition edge_se2.h:41
EIGEN_MAKE_ALIGNED_OPERATOR_NEW EdgeSE2()
Definition edge_se2.cpp:36
virtual void linearizeOplus()
Definition edge_se2.cpp:63
virtual void initialEstimate(const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *to)
Definition edge_se2.cpp:52
SE2 _inverseMeasurement
Definition edge_se2.h:95
virtual bool read(std::istream &is)
read the vertex from a stream, i.e., the internal state of the vertex
Definition edge_se2.cpp:38
virtual void setMeasurement(const SE2 &m)
Definition edge_se2.h:56
virtual bool write(std::ostream &os) const
write the vertex to a stream
Definition edge_se2.cpp:47
Abstract action that operates on a graph entity.
VertexContainer _vertices
const Vertex * vertex(size_t i) const
std::set< Vertex * > VertexSet
A general case Vertex for optimization.
represent SE2
Definition se2.h:43
const Vector2 & translation() const
translational component
Definition se2.h:57
SE2 inverse() const
invert :-)
Definition se2.h:83
const Rotation2D & rotation() const
rotational component
Definition se2.h:61
2D pose Vertex, (x,y,theta)
Definition vertex_se2.h:41
#define RAD2DEG(x)
Definition macros.h:35
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
void drawArrow2D(float len, float head_width, float head_len)
VectorN< 3 > Vector3
Definition eigen_types.h:51
MatrixN< 3 > Matrix3
Definition eigen_types.h:72
constexpr double cst(long double v)
Definition misc.h:60
VectorN< 2 > Vector2
Definition eigen_types.h:50
Property< float > FloatProperty
Definition property.h:150
#define POSE_EDGE_COLOR
#define POSE_EDGE_GHOST_COLOR