g2o
Loading...
Searching...
No Matches
edge_se3_xyzprior.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_xyzprior.h"
28
29#include <cassert>
30
31namespace g2o {
32
35 information().setIdentity();
36 setMeasurement(Vector3::Zero());
37 _cache = 0;
38 _offsetParam = 0;
41}
42
44 assert(_offsetParam);
45 ParameterVector pv(1);
46 pv[0] = _offsetParam;
48 "CACHE_SE3_OFFSET", pv);
49 return _cache != 0;
50}
51
52bool EdgeSE3XYZPrior::read(std::istream& is) {
53 readParamIds(is);
55 return readInformationMatrix(is);
56}
57
58bool EdgeSE3XYZPrior::write(std::ostream& os) const {
59 writeParamIds(os);
61 return writeInformationMatrix(os);
62}
63
65 const VertexSE3* v = static_cast<const VertexSE3*>(_vertices[0]);
66 _error = v->estimate().translation() - _measurement;
67}
68
70 const VertexSE3* v = static_cast<const VertexSE3*>(_vertices[0]);
71 _jacobianOplusXi.block<3, 3>(0, 0) = v->estimate().rotation();
72 _jacobianOplusXi.block<3, 3>(0, 3) = Eigen::Matrix3d::Zero();
73}
74
76 const VertexSE3* v = static_cast<const VertexSE3*>(_vertices[0]);
77 _measurement = v->estimate().translation();
78 return true;
79}
80
82 const OptimizableGraph::VertexSet& /*from_*/,
83 OptimizableGraph::Vertex* /*to_*/) {
84 VertexSE3* v = static_cast<VertexSE3*>(_vertices[0]);
85 assert(v && "Vertex for the Prior edge is not set");
86
87 Isometry3 newEstimate =
88 _offsetParam->offset().inverse() * Eigen::Translation3d(measurement());
89 if (_information.block<3, 3>(0, 0).array().abs().sum() ==
90 0) { // do not set translation, as that part of the information is all
91 // zero
92 newEstimate.translation() = v->estimate().translation();
93 }
94 v->setEstimate(newEstimate);
95}
96
97} // 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
virtual void setMeasurement(const Measurement &m)
Definition base_edge.h:122
InformationType _information
Definition base_edge.h:147
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
BaseFixedSizedEdge< D, Vector3, VertexSE3 >::template JacobianType< D, VertexXi::Dimension > & _jacobianOplusXi
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()
CacheSE3Offset * _cache
virtual bool read(std::istream &is)
read the vertex from a stream, i.e., the internal state of the vertex
virtual void initialEstimate(const OptimizableGraph::VertexSet &, OptimizableGraph::Vertex *)
ParameterSE3Offset * _offsetParam
virtual bool write(std::ostream &os) const
write the vertex to a stream
virtual bool setMeasurementFromState()
virtual void linearizeOplus()
EIGEN_MAKE_ALIGNED_OPERATOR_NEW EdgeSE3XYZPrior()
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
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
Eigen::Transform< double, 3, Eigen::Isometry, Eigen::ColMajor > Isometry3
Definition eigen_types.h:77
std::vector< Parameter * > ParameterVector
Definition parameter.h:54