g2o
Loading...
Searching...
No Matches
edge_se3_line.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_line.h"
28
30
31namespace g2o {
32
34 information().setIdentity();
35 cache = 0;
36 offsetParam = 0;
39 color << 0.0, 0.5, 1.0;
40}
41
42bool EdgeSE3Line3D::read(std::istream& is) {
43 bool state = readParamIds(is);
45 state &= readInformationMatrix(is);
46 return state;
47}
48
49bool EdgeSE3Line3D::write(std::ostream& os) const {
50 writeParamIds(os);
52 return writeInformationMatrix(os);
53}
54
56 const VertexSE3* se3Vertex = static_cast<const VertexSE3*>(_vertices[0]);
57 const VertexLine3D* lineVertex =
58 static_cast<const VertexLine3D*>(_vertices[1]);
59 const Line3D& line = lineVertex->estimate();
60 Line3D localLine = se3Vertex->estimate().inverse() * line;
61 _error = localLine.ominus(_measurement);
62}
63
65 ParameterVector pv(1);
66 pv[0] = offsetParam;
68 "CACHE_SE3_OFFSET", pv);
69 return cache != 0;
70}
71
72#ifdef G2O_HAVE_OPENGL
73EdgeSE3Line3DDrawAction::EdgeSE3Line3DDrawAction()
74 : DrawAction(typeid(EdgeSE3Line3D).name()),
75 _lineLength(nullptr),
76 _lineWidth(nullptr) {}
77
78bool EdgeSE3Line3DDrawAction::refreshPropertyPtrs(
79 HyperGraphElementAction::Parameters* params_) {
80 if (!DrawAction::refreshPropertyPtrs(params_)) {
81 return false;
82 }
83 if (_previousParams) {
84 _lineLength = _previousParams->makeProperty<FloatProperty>(
85 _typeName + "::LINE_LENGTH", 4.0f);
86 _lineWidth = _previousParams->makeProperty<FloatProperty>(
87 _typeName + "::LINE_WIDTH", 2.0f);
88 } else {
89 _lineLength = 0;
90 _lineWidth = 0;
91 }
92 return true;
93}
94
95HyperGraphElementAction* EdgeSE3Line3DDrawAction::operator()(
96 HyperGraph::HyperGraphElement* element,
97 HyperGraphElementAction::Parameters* params_) {
98 if (typeid(*element).name() != _typeName) return nullptr;
99
100 refreshPropertyPtrs(params_);
101 if (!_previousParams) return this;
102
103 if (_show && !_show->value()) return this;
104
105 EdgeSE3Line3D* that = dynamic_cast<EdgeSE3Line3D*>(element);
106
107 if (!that) return this;
108
109 const VertexSE3* robot = dynamic_cast<const VertexSE3*>(that->vertex(0));
110 const VertexLine3D* landmark =
111 dynamic_cast<const VertexLine3D*>(that->vertex(1));
112
113 if (!robot || !landmark) return nullptr;
114
115 if (_lineLength && _lineWidth) {
116 Line3D line = that->measurement();
117 line.normalize();
118 Vector3 direction = line.d();
119 Vector3 npoint = line.d().cross(line.w());
120
121 glPushMatrix();
122 glMultMatrixd(robot->estimate().matrix().cast<double>().eval().data());
123 glColor3f(float(that->color(0)), float(that->color(1)),
124 float(that->color(2)));
125 glLineWidth(float(_lineWidth->value()));
126 glBegin(GL_LINES);
127 glNormal3f(float(npoint.x()), float(npoint.y()), float(npoint.z()));
128 glVertex3f(float(npoint.x() - direction.x() * _lineLength->value() / 2),
129 float(npoint.y() - direction.y() * _lineLength->value() / 2),
130 float(npoint.z() - direction.z() * _lineLength->value() / 2));
131 glVertex3f(float(npoint.x() + direction.x() * _lineLength->value() / 2),
132 float(npoint.y() + direction.y() * _lineLength->value() / 2),
133 float(npoint.z() + direction.z() * _lineLength->value() / 2));
134 glEnd();
135 glPopMatrix();
136 }
137
138 return this;
139}
140#endif
141
142} // namespace g2o
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
virtual bool refreshPropertyPtrs(HyperGraphElementAction::Parameters *params_)
virtual bool resolveCaches()
virtual bool read(std::istream &is)
read the vertex from a stream, i.e., the internal state of the vertex
CacheSE3Offset * cache
virtual bool write(std::ostream &os) const
write the vertex to a stream
ParameterSE3Offset * offsetParam
VertexContainer _vertices
G2O_TYPES_SLAM3D_ADDONS_API Vector4 ominus(const Line3D &line)
Definition line3d.h:158
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.
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
Property< float > FloatProperty
Definition property.h:150