g2o
Loading...
Searching...
No Matches
edge_se2_offset.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_offset.h"
28
29#include <cassert>
30#include <iostream>
31
33
34namespace g2o {
35using namespace std;
36
48
50 assert(_offsetFrom && _offsetTo);
51
52 ParameterVector pv(1);
53 pv[0] = _offsetFrom;
55 "CACHE_SE2_OFFSET", pv);
56 pv[0] = _offsetTo;
58 "CACHE_SE2_OFFSET", pv);
59 return (_cacheFrom && _cacheTo);
60}
61
62bool EdgeSE2Offset::read(std::istream& is) {
63 int pidFrom, pidTo;
64 is >> pidFrom >> pidTo;
65 if (!setParameterId(0, pidFrom)) return false;
66 if (!setParameterId(1, pidTo)) return false;
67
68 Vector3 meas;
69 internal::readVector(is, meas);
70 setMeasurement(SE2(meas));
71 if (is.bad()) return false;
73 if (is.bad()) {
74 // we overwrite the information matrix with the Identity
75 information().setIdentity();
76 }
77 return true;
78}
79
80bool EdgeSE2Offset::write(std::ostream& os) const {
81 os << _offsetFrom->id() << " " << _offsetTo->id() << " ";
82 internal::writeVector(os, measurement().toVector());
83 return writeInformationMatrix(os);
84}
85
88 _error.head<2>() = delta.translation();
89 _error(2) = delta.rotation().angle();
90}
91
93 SE2 delta = _cacheFrom->w2n() * _cacheTo->n2w();
94 setMeasurement(delta);
95 return true;
96}
97
99 OptimizableGraph::Vertex* /*to_*/) {
100 VertexSE2* from = static_cast<VertexSE2*>(_vertices[0]);
101 VertexSE2* to = static_cast<VertexSE2*>(_vertices[1]);
102
103 SE2 virtualMeasurement = _cacheFrom->offsetParam()->offset() * measurement() *
105
106 if (from_.count(from) > 0)
107 to->setEstimate(from->estimate() * virtualMeasurement);
108 else
109 from->setEstimate(to->estimate() * virtualMeasurement.inverse());
110}
111
112} // 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
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
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 SE2 & w2n() const
const ParameterSE2Offset * offsetParam() const
const SE2 & n2w() const
virtual bool setMeasurementFromState()
virtual bool resolveCaches()
CacheSE2Offset * _cacheTo
ParameterSE2Offset * _offsetFrom
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
ParameterSE2Offset * _offsetTo
CacheSE2Offset * _cacheFrom
virtual void initialEstimate(const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *to)
virtual void setMeasurement(const SE2 &m)
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
bool setParameterId(int argNum, int paramId)
A general case Vertex for optimization.
int id() const
Definition parameter.h:44
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
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
Definition jet.h:876