g2o
Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes | List of all members
g2o::deprecated::EdgeSE3Offset Class Reference

Offset edge. More...

#include <edge_se3_offset.h>

Inheritance diagram for g2o::deprecated::EdgeSE3Offset:
Inheritance graph
[legend]
Collaboration diagram for g2o::deprecated::EdgeSE3Offset:
Collaboration graph
[legend]

Public Member Functions

 EdgeSE3Offset ()
 
virtual bool read (std::istream &is)
 read the vertex from a stream, i.e., the internal state of the vertex More...
 
virtual bool write (std::ostream &os) const
 write the vertex to a stream More...
 
void computeError ()
 
virtual void setMeasurement (const SE3Quat &m)
 
virtual bool setMeasurementData (const double *d)
 
virtual bool getMeasurementData (double *d) const
 
void linearizeOplus ()
 
virtual int measurementDimension () const
 
virtual bool setMeasurementFromState ()
 
virtual double initialEstimatePossible (const OptimizableGraph::VertexSet &, OptimizableGraph::Vertex *)
 
virtual void initialEstimate (const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *to)
 
- Public Member Functions inherited from g2o::BaseBinaryEdge< 6, SE3Quat, VertexSE3, VertexSE3 >
 BaseBinaryEdge ()
 
virtual OptimizableGraph::VertexcreateFrom ()
 
virtual OptimizableGraph::VertexcreateTo ()
 
virtual OptimizableGraph::VertexcreateVertex (int i)
 
virtual void resize (size_t size)
 
virtual bool allVerticesFixed () const
 
virtual void linearizeOplus (JacobianWorkspace &jacobianWorkspace)
 
const JacobianXiOplusTypejacobianOplusXi () const
 returns the result of the linearization in the manifold space for the node xi More...
 
const JacobianXjOplusTypejacobianOplusXj () const
 returns the result of the linearization in the manifold space for the node xj More...
 
virtual void constructQuadraticForm ()
 
virtual void mapHessianMemory (double *d, int i, int j, bool rowMajor)
 
- Public Member Functions inherited from g2o::BaseEdge< D, SE3Quat >
 BaseEdge ()
 
virtual ~BaseEdge ()
 
virtual double chi2 () const
 computes the chi2 based on the cached error value, only valid after computeError has been called. More...
 
virtual const double * errorData () const
 returns the error vector cached after calling the computeError; More...
 
virtual double * errorData ()
 
const ErrorVectorerror () const
 
ErrorVectorerror ()
 
EIGEN_STRONG_INLINE const InformationTypeinformation () const
 information matrix of the constraint More...
 
EIGEN_STRONG_INLINE InformationTypeinformation ()
 
EIGEN_STRONG_INLINE void setInformation (const InformationType &information)
 
virtual const double * informationData () const
 returns the memory of the information matrix, usable for example with a Eigen::Map<MatrixXD> More...
 
virtual double * informationData ()
 
EIGEN_STRONG_INLINE const Measurementmeasurement () const
 accessor functions for the measurement represented by the edge More...
 
virtual int rank () const
 
- Public Member Functions inherited from g2o::OptimizableGraph::Edge
 Edge ()
 
virtual ~Edge ()
 
virtual Edgeclone () const
 
RobustKernelrobustKernel () const
 if NOT NULL, error of this edge will be robustifed with the kernel More...
 
void setRobustKernel (RobustKernel *ptr)
 
int level () const
 returns the level of the edge More...
 
void setLevel (int l)
 sets the level of the edge More...
 
int dimension () const
 returns the dimensions of the error function More...
 
 G2O_ATTRIBUTE_DEPRECATED (virtual Vertex *createFrom())
 
 G2O_ATTRIBUTE_DEPRECATED (virtual Vertex *createTo())
 
long long internalId () const
 the internal ID of the edge More...
 
OptimizableGraphgraph ()
 
const OptimizableGraphgraph () const
 
bool setParameterId (int argNum, int paramId)
 
const Parameterparameter (int argNo) const
 
size_t numParameters () const
 
void resizeParameters (size_t newSize)
 
- Public Member Functions inherited from g2o::HyperGraph::Edge
 Edge (int id=InvalidId)
 creates and empty edge with no vertices More...
 
const VertexContainervertices () const
 
VertexContainervertices ()
 
const Vertexvertex (size_t i) const
 
Vertexvertex (size_t i)
 
void setVertex (size_t i, Vertex *v)
 
int id () const
 
void setId (int id)
 
virtual HyperGraphElementType elementType () const
 
int numUndefinedVertices () const
 
- Public Member Functions inherited from g2o::HyperGraph::HyperGraphElement
virtual ~HyperGraphElement ()
 
HyperGraphElementclone () const
 
- Public Member Functions inherited from g2o::HyperGraph::DataContainer
 DataContainer ()
 
virtual ~DataContainer ()
 
const DatauserData () const
 the user data associated with this vertex More...
 
DatauserData ()
 
void setUserData (Data *obs)
 
void addUserData (Data *obs)
 

Public Attributes

 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
 

Protected Member Functions

virtual bool resolveCaches ()
 
- Protected Member Functions inherited from g2o::BaseEdge< D, SE3Quat >
InformationType robustInformation (const Vector3D &rho)
 
- Protected Member Functions inherited from g2o::OptimizableGraph::Edge
template<typename ParameterType >
bool installParameter (ParameterType *&p, size_t argNo, int paramId=-1)
 
template<typename CacheType >
void resolveCache (CacheType *&cache, OptimizableGraph::Vertex *, const std::string &_type, const ParameterVector &parameters)
 
bool resolveParameters ()
 

Protected Attributes

SE3Quat _inverseMeasurement
 
ParameterSE3Offset_offsetFrom
 
ParameterSE3Offset_offsetTo
 
CacheSE3Offset_cacheFrom
 
CacheSE3Offset_cacheTo
 
- Protected Attributes inherited from g2o::BaseBinaryEdge< 6, SE3Quat, VertexSE3, VertexSE3 >
bool _hessianRowMajor
 
HessianBlockType _hessian
 
HessianBlockTransposedType _hessianTransposed
 
JacobianXiOplusType _jacobianOplusXi
 
JacobianXjOplusType _jacobianOplusXj
 
- Protected Attributes inherited from g2o::BaseEdge< D, SE3Quat >
Measurement _measurement
 
InformationType _information
 
ErrorVector _error
 
- Protected Attributes inherited from g2o::OptimizableGraph::Edge
int _dimension
 
int _level
 
RobustKernel_robustKernel
 
long long _internalId
 
std::vector< int > _cacheIds
 
std::vector< std::string > _parameterTypes
 
std::vector< Parameter ** > _parameters
 
std::vector< int > _parameterIds
 
- Protected Attributes inherited from g2o::HyperGraph::Edge
VertexContainer _vertices
 
int _id
 unique id More...
 
- Protected Attributes inherited from g2o::HyperGraph::DataContainer
Data_userData
 

Additional Inherited Members

- Public Types inherited from g2o::BaseBinaryEdge< 6, SE3Quat, VertexSE3, VertexSE3 >
typedef VertexSE3 VertexXiType
 
typedef VertexSE3 VertexXjType
 
typedef BaseEdge< D, SE3Quat >::Measurement Measurement
 
typedef Eigen::Matrix< double, D, Di, D==1?Eigen::RowMajor:Eigen::ColMajor >::AlignedMapType JacobianXiOplusType
 
typedef Eigen::Matrix< double, D, Dj, D==1?Eigen::RowMajor:Eigen::ColMajor >::AlignedMapType JacobianXjOplusType
 
typedef BaseEdge< D, SE3Quat >::ErrorVector ErrorVector
 
typedef BaseEdge< D, SE3Quat >::InformationType InformationType
 
typedef Eigen::Map< Eigen::Matrix< double, Di, Dj, Di==1?Eigen::RowMajor:Eigen::ColMajor >, Eigen::Matrix< double, Di, Dj, Di==1?Eigen::RowMajor:Eigen::ColMajor >::Flags &Eigen::AlignedBit?Eigen::Aligned:Eigen::Unaligned > HessianBlockType
 
typedef Eigen::Map< Eigen::Matrix< double, Dj, Di, Dj==1?Eigen::RowMajor:Eigen::ColMajor >, Eigen::Matrix< double, Dj, Di, Dj==1?Eigen::RowMajor:Eigen::ColMajor >::Flags &Eigen::AlignedBit?Eigen::Aligned:Eigen::Unaligned > HessianBlockTransposedType
 
- Public Types inherited from g2o::BaseEdge< D, SE3Quat >
typedef SE3Quat Measurement
 
typedef Eigen::Matrix< double, D, 1, Eigen::ColMajor > ErrorVector
 
typedef Eigen::Matrix< double, D, D, Eigen::ColMajor > InformationType
 
- Static Public Attributes inherited from g2o::BaseBinaryEdge< 6, SE3Quat, VertexSE3, VertexSE3 >
static const int Di
 
static const int Dj
 
static const int Dimension
 
- Static Public Attributes inherited from g2o::BaseEdge< D, SE3Quat >
static const int Dimension
 

Detailed Description

Offset edge.

Definition at line 44 of file edge_se3_offset.h.

Constructor & Destructor Documentation

g2o::deprecated::EdgeSE3Offset::EdgeSE3Offset ( )

Definition at line 38 of file edge_se3_offset.cpp.

References _cacheFrom, _cacheTo, _offsetFrom, _offsetTo, g2o::BaseEdge< D, SE3Quat >::information(), g2o::OptimizableGraph::Edge::installParameter(), and g2o::OptimizableGraph::Edge::resizeParameters().

38  : BaseBinaryEdge<6, SE3Quat, VertexSE3, VertexSE3>() {
39  information().setIdentity();
40  _offsetFrom = 0;
41  _offsetTo = 0;
42  _cacheFrom = 0;
43  _cacheTo = 0;
47  }
bool installParameter(ParameterType *&p, size_t argNo, int paramId=-1)
ParameterSE3Offset * _offsetTo
void resizeParameters(size_t newSize)
EIGEN_STRONG_INLINE const InformationType & information() const
information matrix of the constraint
Definition: base_edge.h:67
ParameterSE3Offset * _offsetFrom

Member Function Documentation

void g2o::deprecated::EdgeSE3Offset::computeError ( )
virtual

Implements g2o::OptimizableGraph::Edge.

Definition at line 99 of file edge_se3_offset.cpp.

References _cacheFrom, _cacheTo, g2o::BaseEdge< D, SE3Quat >::_error, _inverseMeasurement, g2o::deprecated::CacheSE3Offset::n2w(), g2o::SE3Quat::rotation(), g2o::SE3Quat::translation(), and g2o::deprecated::CacheSE3Offset::w2n().

99  {
100  SE3Quat delta=_inverseMeasurement * _cacheFrom->w2n() * _cacheTo->n2w();
101  _error.head<3>() = delta.translation();
102  // The analytic Jacobians assume the error in this special form (w beeing positive)
103  if (delta.rotation().w() < 0.)
104  _error.tail<3>() = - delta.rotation().vec();
105  else
106  _error.tail<3>() = delta.rotation().vec();
107  }
virtual bool g2o::deprecated::EdgeSE3Offset::getMeasurementData ( double *  m) const
inlinevirtual

writes the measurement to an array of double

Returns
true on success

Reimplemented from g2o::OptimizableGraph::Edge.

Definition at line 68 of file edge_se3_offset.h.

68  {
69  Eigen::Map<Vector7d> v(d);
70  v = _measurement.toVector();
71  return true;
72  }
Vector7d toVector() const
Definition: se3quat.h:135
void g2o::deprecated::EdgeSE3Offset::initialEstimate ( const OptimizableGraph::VertexSet ,
OptimizableGraph::Vertex  
)
virtual

set the estimate of the to vertex, based on the estimate of the from vertices in the edge.

Reimplemented from g2o::BaseEdge< D, SE3Quat >.

Definition at line 143 of file edge_se3_offset.cpp.

References _cacheFrom, _cacheTo, g2o::HyperGraph::Edge::_vertices, g2o::BaseVertex< D, T >::estimate(), g2o::SE3Quat::inverse(), g2o::BaseEdge< D, SE3Quat >::measurement(), g2o::deprecated::ParameterSE3Offset::offset(), g2o::deprecated::CacheSE3Offset::offsetParam(), and g2o::BaseVertex< D, T >::setEstimate().

143  {
144  VertexSE3 *from = static_cast<VertexSE3*>(_vertices[0]);
145  VertexSE3 *to = static_cast<VertexSE3*>(_vertices[1]);
146 
147  SE3Quat virtualMeasurement = _cacheFrom->offsetParam()->offset() * measurement() * _cacheTo->offsetParam()->offset().inverse();
148 
149  if (from_.count(from) > 0) {
150  to->setEstimate(from->estimate() * virtualMeasurement);
151  } else
152  from->setEstimate(to->estimate() * virtualMeasurement.inverse());
153  }
const SE3Quat & offset() const
return the offset as SE3Quat
SE3Quat inverse() const
Definition: se3quat.h:120
EIGEN_STRONG_INLINE const Measurement & measurement() const
accessor functions for the measurement represented by the edge
Definition: base_edge.h:75
const ParameterSE3Offset * offsetParam() const
VertexContainer _vertices
Definition: hyper_graph.h:202
virtual double g2o::deprecated::EdgeSE3Offset::initialEstimatePossible ( const OptimizableGraph::VertexSet from,
OptimizableGraph::Vertex to 
)
inlinevirtual

override in your class if it's possible to initialize the vertices in certain combinations. The return value may correspond to the cost for initiliaizng the vertex but should be positive if the initialization is possible and negative if not possible.

Reimplemented from g2o::OptimizableGraph::Edge.

Definition at line 80 of file edge_se3_offset.h.

81  {
82  return 1.;
83  }
void g2o::deprecated::EdgeSE3Offset::linearizeOplus ( )
virtual

Linearizes the oplus operator in the vertex, and stores the result in temporary variables _jacobianOplusXi and _jacobianOplusXj

Reimplemented from g2o::BaseBinaryEdge< 6, SE3Quat, VertexSE3, VertexSE3 >.

Definition at line 115 of file edge_se3_offset.cpp.

References _cacheFrom, _cacheTo, g2o::BaseBinaryEdge< 6, SE3Quat, VertexSE3, VertexSE3 >::_jacobianOplusXi, g2o::BaseBinaryEdge< 6, SE3Quat, VertexSE3, VertexSE3 >::_jacobianOplusXj, g2o::BaseEdge< D, SE3Quat >::_measurement, g2o::HyperGraph::Edge::_vertices, g2o::BaseVertex< D, T >::estimate(), g2o::deprecated::ParameterSE3Offset::offset(), g2o::deprecated::CacheSE3Offset::offsetParam(), g2o::SE3Quat::rotation(), and g2o::SE3Quat::translation().

115  {
116  //BaseBinaryEdge<6, SE3Quat, VertexSE3, VertexSE3>::linearizeOplus();
117 
118  VertexSE3 *from = static_cast<VertexSE3*>(_vertices[0]);
119  VertexSE3 *to = static_cast<VertexSE3*>(_vertices[1]);
120  Eigen::Isometry3d E;
121  Eigen::Isometry3d Z, Xi, Xj, Pi, Pj;
122  Xi=from->estimate().rotation().toRotationMatrix();
123  Xi.translation()=from->estimate().translation();
124  Xj=to->estimate().rotation().toRotationMatrix();
125  Xj.translation()=to->estimate().translation();
126  Pi=_cacheFrom->offsetParam()->offset().rotation().toRotationMatrix();
127  Pi.translation()=_cacheFrom->offsetParam()->offset().translation();
128  Pj=_cacheTo->offsetParam()->offset().rotation().toRotationMatrix();
129  Pj.translation()=_cacheTo->offsetParam()->offset().translation();
130  Z=_measurement.rotation().toRotationMatrix();
131  Z.translation()=_measurement.translation();
132  // Matrix6d Ji, Jj;
133  // computeSE3Gradient(E, Ji , Jj,
134  // Z, Pi, Xi, Pj, Xj);
135  // cerr << "Ji:" << endl;
136  // cerr << Ji-_jacobianOplusXi << endl;
137  // cerr << "Jj:" << endl;
138  // cerr << Jj-_jacobianOplusXj << endl;
139  internal::computeEdgeSE3Gradient<JacobianXiOplusType>(E, _jacobianOplusXi , _jacobianOplusXj,
140  Z, Xi, Xj, Pi, Pj);
141  }
const SE3Quat & offset() const
return the offset as SE3Quat
const Eigen::Quaterniond & rotation() const
Definition: se3quat.h:97
const ParameterSE3Offset * offsetParam() const
const Vector3D & translation() const
Definition: se3quat.h:93
VertexContainer _vertices
Definition: hyper_graph.h:202
virtual int g2o::deprecated::EdgeSE3Offset::measurementDimension ( ) const
inlinevirtual

returns the dimension of the measurement in the extended representation which is used by get/setMeasurement;

Reimplemented from g2o::OptimizableGraph::Edge.

Definition at line 76 of file edge_se3_offset.h.

76 {return 7;}
bool g2o::deprecated::EdgeSE3Offset::read ( std::istream &  is)
virtual

read the vertex from a stream, i.e., the internal state of the vertex

Implements g2o::OptimizableGraph::Edge.

Definition at line 60 of file edge_se3_offset.cpp.

References g2o::BaseEdge< D, SE3Quat >::information(), setMeasurement(), and g2o::OptimizableGraph::Edge::setParameterId().

60  {
61  int pidFrom, pidTo;
62  is >> pidFrom >> pidTo ;
63  if (! setParameterId(0,pidFrom))
64  return false;
65  if (! setParameterId(1,pidTo))
66  return false;
67 
68  Vector7d meas;
69  for (int i=0; i<7; i++)
70  is >> meas[i];
71  setMeasurement(SE3Quat(meas));
72 
73  if (is.bad()) {
74  return false;
75  }
76  for ( int i=0; i<information().rows() && is.good(); i++)
77  for (int j=i; j<information().cols() && is.good(); j++){
78  is >> information()(i,j);
79  if (i!=j)
80  information()(j,i)=information()(i,j);
81  }
82  if (is.bad()) {
83  // we overwrite the information matrix with the Identity
84  information().setIdentity();
85  }
86  return true;
87  }
virtual void setMeasurement(const SE3Quat &m)
Eigen::Matrix< double, 7, 1 > Vector7d
Definition: sim3.h:35
bool setParameterId(int argNum, int paramId)
EIGEN_STRONG_INLINE const InformationType & information() const
information matrix of the constraint
Definition: base_edge.h:67
bool g2o::deprecated::EdgeSE3Offset::resolveCaches ( )
protectedvirtual

Reimplemented from g2o::OptimizableGraph::Edge.

Definition at line 49 of file edge_se3_offset.cpp.

References _cacheFrom, _cacheTo, _offsetFrom, _offsetTo, g2o::HyperGraph::Edge::_vertices, and g2o::OptimizableGraph::Edge::resolveCache().

49  {
50  assert(_offsetFrom && _offsetTo);
51 
52  ParameterVector pv(2);
53  pv[0]=_offsetFrom;
54  resolveCache(_cacheFrom, (OptimizableGraph::Vertex*)_vertices[0],"CACHE_SE3_OFFSET",pv);
55  pv[1]=_offsetTo;
56  resolveCache(_cacheTo, (OptimizableGraph::Vertex*)_vertices[1],"CACHE_SE3_OFFSET",pv);
57  return (_cacheFrom && _cacheTo);
58  }
class G2O_CORE_API Vertex
void resolveCache(CacheType *&cache, OptimizableGraph::Vertex *, const std::string &_type, const ParameterVector &parameters)
Definition: cache.h:122
std::vector< Parameter * > ParameterVector
Definition: parameter.h:52
ParameterSE3Offset * _offsetTo
ParameterSE3Offset * _offsetFrom
VertexContainer _vertices
Definition: hyper_graph.h:202
virtual void g2o::deprecated::EdgeSE3Offset::setMeasurement ( const SE3Quat m)
inlinevirtual

Reimplemented from g2o::BaseEdge< D, SE3Quat >.

Definition at line 56 of file edge_se3_offset.h.

References g2o::SE3Quat::inverse().

Referenced by read(), and setMeasurementFromState().

56  {
57  _measurement = m;
59  }
SE3Quat inverse() const
Definition: se3quat.h:120
virtual bool g2o::deprecated::EdgeSE3Offset::setMeasurementData ( const double *  m)
inlinevirtual

sets the measurement from an array of double

Returns
true on success

Reimplemented from g2o::OptimizableGraph::Edge.

Definition at line 61 of file edge_se3_offset.h.

61  {
62  Eigen::Map<const Vector7d> v(d);
65  return true;
66  }
SE3Quat inverse() const
Definition: se3quat.h:120
void fromVector(const Vector7d &v)
Definition: se3quat.h:147
bool g2o::deprecated::EdgeSE3Offset::setMeasurementFromState ( )
virtual

sets the estimate to have a zero error, based on the current value of the state variables returns false if not supported.

Reimplemented from g2o::OptimizableGraph::Edge.

Definition at line 109 of file edge_se3_offset.cpp.

References _cacheFrom, _cacheTo, g2o::deprecated::CacheSE3Offset::n2w(), setMeasurement(), and g2o::deprecated::CacheSE3Offset::w2n().

109  {
110  SE3Quat delta = _cacheFrom->w2n() * _cacheTo->n2w();
111  setMeasurement(delta);
112  return true;
113  }
virtual void setMeasurement(const SE3Quat &m)
bool g2o::deprecated::EdgeSE3Offset::write ( std::ostream &  os) const
virtual

write the vertex to a stream

Implements g2o::OptimizableGraph::Edge.

Definition at line 89 of file edge_se3_offset.cpp.

References _offsetFrom, _offsetTo, g2o::Parameter::id(), g2o::BaseEdge< D, SE3Quat >::information(), and g2o::BaseEdge< D, SE3Quat >::measurement().

89  {
90  os << _offsetFrom->id() << " " << _offsetTo->id() << " ";
91  for (int i=0; i<7; i++) os << measurement()[i] << " ";
92  for (int i=0; i<information().rows(); i++)
93  for (int j=i; j<information().cols(); j++) {
94  os << information()(i,j) << " ";
95  }
96  return os.good();
97  }
int id() const
Definition: parameter.h:45
ParameterSE3Offset * _offsetTo
EIGEN_STRONG_INLINE const InformationType & information() const
information matrix of the constraint
Definition: base_edge.h:67
ParameterSE3Offset * _offsetFrom
EIGEN_STRONG_INLINE const Measurement & measurement() const
accessor functions for the measurement represented by the edge
Definition: base_edge.h:75

Member Data Documentation

CacheSE3Offset* g2o::deprecated::EdgeSE3Offset::_cacheFrom
protected
CacheSE3Offset * g2o::deprecated::EdgeSE3Offset::_cacheTo
protected
SE3Quat g2o::deprecated::EdgeSE3Offset::_inverseMeasurement
protected

Definition at line 88 of file edge_se3_offset.h.

Referenced by computeError().

ParameterSE3Offset* g2o::deprecated::EdgeSE3Offset::_offsetFrom
protected

Definition at line 90 of file edge_se3_offset.h.

Referenced by EdgeSE3Offset(), resolveCaches(), and write().

ParameterSE3Offset * g2o::deprecated::EdgeSE3Offset::_offsetTo
protected

Definition at line 90 of file edge_se3_offset.h.

Referenced by EdgeSE3Offset(), resolveCaches(), and write().

g2o::deprecated::EdgeSE3Offset::EIGEN_MAKE_ALIGNED_OPERATOR_NEW

Definition at line 46 of file edge_se3_offset.h.


The documentation for this class was generated from the following files: