g2o
Loading...
Searching...
No Matches
edge_se3_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_se3_offset.h"
28
29#include <cassert>
30#include <iostream>
31
34
35namespace g2o {
36using namespace std;
37using namespace Eigen;
38
49
51 assert(_offsetFrom && _offsetTo);
52
53 ParameterVector pv(2);
54 pv[0] = _offsetFrom;
56 "CACHE_SE3_OFFSET", pv);
57 pv[0] = _offsetTo;
59 "CACHE_SE3_OFFSET", pv);
60 return (_cacheFrom && _cacheTo);
61}
62
63bool EdgeSE3Offset::read(std::istream& is) {
64 bool state = readParamIds(is);
65
66 Vector7 meas;
67 state &= internal::readVector(is, meas);
68 // normalize the quaternion to recover numerical precision lost by storing as
69 // human readable text
70 Vector4::MapType(meas.data() + 3).normalize();
72
73 state &= readInformationMatrix(is);
74 return state;
75}
76
77bool EdgeSE3Offset::write(std::ostream& os) const {
78 writeParamIds(os);
81 return os.good();
82}
83
88
90 Isometry3 delta = _cacheFrom->w2n() * _cacheTo->n2w();
91 setMeasurement(delta);
92 return true;
93}
94
96 // BaseBinaryEdge<6, SE3Quat, VertexSE3, VertexSE3>::linearizeOplus();
97
98 VertexSE3* from = static_cast<VertexSE3*>(_vertices[0]);
99 VertexSE3* to = static_cast<VertexSE3*>(_vertices[1]);
100 Isometry3 E;
101 const Isometry3& Xi = from->estimate();
102 const Isometry3& Xj = to->estimate();
103 const Isometry3& Pi = _cacheFrom->offsetParam()->offset();
104 const Isometry3& Pj = _cacheTo->offsetParam()->offset();
105 const Isometry3& Z = _measurement;
107 Xj, Pi, Pj);
108}
109
111 OptimizableGraph::Vertex* /*to_*/) {
112 VertexSE3* from = static_cast<VertexSE3*>(_vertices[0]);
113 VertexSE3* to = static_cast<VertexSE3*>(_vertices[1]);
114
115 Isometry3 virtualMeasurement = _cacheFrom->offsetParam()->offset() *
116 measurement() *
117 _cacheTo->offsetParam()->offset().inverse();
118
119 if (from_.count(from) > 0) {
120 to->setEstimate(from->estimate() * virtualMeasurement);
121 } else
122 from->setEstimate(to->estimate() * virtualMeasurement.inverse());
123}
124
125} // 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
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
void setEstimate(const EstimateType &et)
set the estimate for the vertex also calls updateCache()
const Isometry3 & w2n() const
const Isometry3 & n2w() const
const ParameterSE3Offset * offsetParam() const
virtual void initialEstimate(const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *to)
ParameterSE3Offset * _offsetFrom
virtual bool write(std::ostream &os) const
write the vertex to a stream
CacheSE3Offset * _cacheFrom
virtual bool setMeasurementFromState()
ParameterSE3Offset * _offsetTo
virtual bool read(std::istream &is)
read the vertex from a stream, i.e., the internal state of the vertex
CacheSE3Offset * _cacheTo
virtual bool resolveCaches()
Edge between two 3D pose vertices.
Definition edge_se3.h:44
virtual void setMeasurement(const Isometry3 &m)
Definition edge_se3.h:53
Isometry3 _inverseMeasurement
Definition edge_se3.h:86
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
A general case Vertex for optimization.
const Isometry3 & offset() const
rotation of the offset as 3x3 rotation matrix
3D pose Vertex, represented as an Isometry3
Definition vertex_se3.h:50
Definition jet.h:938
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
std::vector< Parameter * > ParameterVector
Definition parameter.h:54
Definition jet.h:876