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

#include <edge_se2_lotsofxy.h>

Inheritance diagram for g2o::EdgeSE2LotsOfXY:
Inheritance graph
[legend]
Collaboration diagram for g2o::EdgeSE2LotsOfXY:
Collaboration graph
[legend]

Public Member Functions

 EdgeSE2LotsOfXY ()
 
void setDimension (int dimension_)
 
void setSize (int vertices)
 
virtual void computeError ()
 
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...
 
virtual bool setMeasurementFromState ()
 
virtual void initialEstimate (const OptimizableGraph::VertexSet &, OptimizableGraph::Vertex *)
 
virtual double initialEstimatePossible (const OptimizableGraph::VertexSet &, OptimizableGraph::Vertex *)
 
virtual void linearizeOplus ()
 
- Public Member Functions inherited from g2o::BaseMultiEdge<-1, VectorXD >
 BaseMultiEdge ()
 
virtual void linearizeOplus (JacobianWorkspace &jacobianWorkspace)
 
virtual void resize (size_t size)
 
virtual bool allVerticesFixed () const
 
virtual void constructQuadraticForm ()
 
virtual void mapHessianMemory (double *d, int i, int j, bool rowMajor)
 
- Public Member Functions inherited from g2o::BaseEdge< D, VectorXD >
 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 void setMeasurement (const Measurement &m)
 
virtual int rank () const
 
- Public Member Functions inherited from g2o::OptimizableGraph::Edge
 Edge ()
 
virtual ~Edge ()
 
virtual Edgeclone () const
 
virtual bool setMeasurementData (const double *m)
 
virtual bool getMeasurementData (double *m) const
 
virtual int measurementDimension () 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())
 
virtual VertexcreateVertex (int)
 
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 Attributes

unsigned int _observedPoints
 
- Protected Attributes inherited from g2o::BaseMultiEdge<-1, VectorXD >
std::vector< HessianHelper > _hessian
 
std::vector< JacobianType, Eigen::aligned_allocator< JacobianType > > _jacobianOplus
 jacobians of the edge (w.r.t. oplus) More...
 
- Protected Attributes inherited from g2o::BaseEdge< D, VectorXD >
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::BaseMultiEdge<-1, VectorXD >
typedef BaseEdge< D, VectorXD >::Measurement Measurement
 
typedef MatrixXD::MapType JacobianType
 
typedef BaseEdge< D, VectorXD >::ErrorVector ErrorVector
 
typedef BaseEdge< D, VectorXD >::InformationType InformationType
 
typedef Eigen::Map< MatrixXD, MatrixXD::Flags &Eigen::AlignedBit?Eigen::Aligned:Eigen::Unaligned > HessianBlockType
 
- Public Types inherited from g2o::BaseEdge< D, VectorXD >
typedef VectorXD 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::BaseMultiEdge<-1, VectorXD >
static const int Dimension
 
- Static Public Attributes inherited from g2o::BaseEdge< D, VectorXD >
static const int Dimension
 
- Protected Member Functions inherited from g2o::BaseMultiEdge<-1, VectorXD >
void computeQuadraticForm (const InformationType &omega, const ErrorVector &weightedError)
 
- Protected Member Functions inherited from g2o::BaseEdge< D, VectorXD >
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 ()
 
virtual bool resolveCaches ()
 

Detailed Description

Definition at line 12 of file edge_se2_lotsofxy.h.

Constructor & Destructor Documentation

g2o::EdgeSE2LotsOfXY::EdgeSE2LotsOfXY ( )

Definition at line 10 of file edge_se2_lotsofxy.cpp.

References g2o::BaseMultiEdge<-1, VectorXD >::resize().

10  : BaseMultiEdge<-1,VectorXD>(){
11  resize(0);
12  }
Eigen::Matrix< double, Eigen::Dynamic, 1, Eigen::ColMajor > VectorXD
Definition: eigen_types.h:48
virtual void resize(size_t size)

Member Function Documentation

void g2o::EdgeSE2LotsOfXY::computeError ( )
virtual

Implements g2o::OptimizableGraph::Edge.

Definition at line 14 of file edge_se2_lotsofxy.cpp.

References g2o::BaseEdge< D, VectorXD >::_error, g2o::BaseEdge< D, VectorXD >::_measurement, _observedPoints, g2o::HyperGraph::Edge::_vertices, g2o::BaseVertex< D, T >::estimate(), and g2o::SE2::inverse().

14  {
15  VertexSE2 * pose = static_cast<VertexSE2 *> (_vertices[0]);
16 
17  for(unsigned int i=0; i<_observedPoints; i++){
18  VertexPointXY * xy = static_cast<VertexPointXY *> (_vertices[1+i]);
19  Vector2D m = pose->estimate().inverse() * xy->estimate();
20 
21  unsigned int index = 2*i;
22  _error[index] = m[0] - _measurement[index];
23  _error[index+1] = m[1] - _measurement[index+1];
24  }
25  }
Eigen::Matrix< double, 2, 1, Eigen::ColMajor > Vector2D
Definition: eigen_types.h:45
unsigned int _observedPoints
VertexContainer _vertices
Definition: hyper_graph.h:202
void g2o::EdgeSE2LotsOfXY::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, VectorXD >.

Definition at line 121 of file edge_se2_lotsofxy.cpp.

References g2o::BaseEdge< D, VectorXD >::_measurement, _observedPoints, g2o::HyperGraph::Edge::_vertices, g2o::BaseVertex< D, T >::estimate(), g2o::HyperGraph::Vertex::id(), initialEstimatePossible(), and g2o::BaseVertex< D, T >::setEstimate().

121  {
122  (void) toEstimate;
123 
124  assert(initialEstimatePossible(fixed, toEstimate) && "Bad vertices specified");
125 
126  VertexSE2 * pose = static_cast<VertexSE2 *>(_vertices[0]);
127 
128 #ifdef _MSC_VER
129  std::vector<bool> estimate_this(_observedPoints, true);
130 #else
131  bool estimate_this[_observedPoints];
132  for(unsigned int i=0; i<_observedPoints; i++){
133  estimate_this[i] = true;
134  }
135 #endif
136 
137  for(std::set<HyperGraph::Vertex*>::iterator it=fixed.begin(); it!=fixed.end(); it++){
138  for(unsigned int i=1; i<_vertices.size(); i++){
139  VertexPointXY * vert = static_cast<VertexPointXY *>(_vertices[i]);
140  if(vert->id() == (*it)->id()) estimate_this[i-1] = false;
141  }
142  }
143 
144  for(unsigned int i=1; i<_vertices.size(); i++){
145  if(estimate_this[i-1]){
146  unsigned int index = 2*(i-1);
147  Vector2D submeas(_measurement[index], _measurement[index+1]);
148  VertexPointXY * vert = static_cast<VertexPointXY *>(_vertices[i]);
149  vert->setEstimate(pose->estimate() * submeas);
150  }
151  }
152  }
Eigen::Matrix< double, 2, 1, Eigen::ColMajor > Vector2D
Definition: eigen_types.h:45
virtual double initialEstimatePossible(const OptimizableGraph::VertexSet &, OptimizableGraph::Vertex *)
unsigned int _observedPoints
VertexContainer _vertices
Definition: hyper_graph.h:202
double g2o::EdgeSE2LotsOfXY::initialEstimatePossible ( const OptimizableGraph::VertexSet from,
OptimizableGraph::Vertex to 
)
virtual

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 155 of file edge_se2_lotsofxy.cpp.

References g2o::HyperGraph::Edge::_vertices.

Referenced by initialEstimate().

155  {
156  (void) toEstimate;
157 
158  for(std::set<HyperGraph::Vertex *>::iterator it=fixed.begin(); it!=fixed.end(); it++){
159  if(_vertices[0]->id() == (*it)->id()){
160  return 1.0;
161  }
162  }
163 
164  return -1.0;
165  }
VertexContainer _vertices
Definition: hyper_graph.h:202
void g2o::EdgeSE2LotsOfXY::linearizeOplus ( )
virtual

Linearizes the oplus operator in the vertex, and stores the result in temporary variable vector _jacobianOplus

Reimplemented from g2o::BaseMultiEdge<-1, VectorXD >.

Definition at line 75 of file edge_se2_lotsofxy.cpp.

References g2o::BaseMultiEdge<-1, VectorXD >::_jacobianOplus, g2o::HyperGraph::Edge::_vertices, g2o::BaseVertex< D, T >::estimate(), g2o::SE2::rotation(), and g2o::SE2::translation().

75  {
76  const VertexSE2* vi = static_cast<const VertexSE2*>(_vertices[0]);
77  const double& x1 = vi->estimate().translation()[0];
78  const double& y1 = vi->estimate().translation()[1];
79  const double& th1 = vi->estimate().rotation().angle();
80 
81  double ct = cos(th1) ;
82  double st = sin(th1) ;
83 
84  MatrixXD Ji;
85  unsigned int rows = 2*(_vertices.size()-1);
86  Ji.resize(rows, 3);
87  Ji.fill(0);
88 
89  Matrix2D poseRot; // inverse of the rotation matrix associated to the pose
90  poseRot << ct , st ,
91  -st , ct ;
92 
93  Matrix2D minusPoseRot = -poseRot;
94 
95 
96  for(unsigned int i=1; i<_vertices.size(); i++){
98 
99  const double& x2 = point->estimate()[0];
100  const double& y2 = point->estimate()[1];
101 
102  unsigned int index = 2*(i-1);
103 
104  Ji.block<2,2>(index,0) = minusPoseRot;
105 
106  Ji(index,2) = ct * (y2-y1) + st * (x1 - x2);
107  Ji(index+1,2) = st * (y1-y2) + ct * (x1 - x2);
108 
109 
110  MatrixXD Jj;
111  Jj.resize(rows, 2);
112  Jj.fill(0);
113  Jj.block<2,2>(index, 0) = poseRot;
114 
115  _jacobianOplus[i] = Jj;
116  }
117  _jacobianOplus[0] = Ji;
118  }
Eigen::Matrix< double, 2, 2, Eigen::ColMajor > Matrix2D
Definition: eigen_types.h:60
const EstimateType & estimate() const
return the current estimate of the vertex
Definition: base_vertex.h:99
Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::ColMajor > MatrixXD
Definition: eigen_types.h:63
std::vector< JacobianType, Eigen::aligned_allocator< JacobianType > > _jacobianOplus
jacobians of the edge (w.r.t. oplus)
VertexContainer _vertices
Definition: hyper_graph.h:202
bool g2o::EdgeSE2LotsOfXY::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 27 of file edge_se2_lotsofxy.cpp.

References g2o::BaseEdge< D, VectorXD >::_measurement, _observedPoints, g2o::BaseEdge< D, VectorXD >::information(), and setSize().

27  {
28  is >> _observedPoints;
29  setSize(_observedPoints + 1);
30 
31  // read the measurements
32  for(unsigned int i=0; i<_observedPoints; i++){
33  unsigned int index = 2*i;
34  is >> _measurement[index] >> _measurement[index+1];
35  }
36 
37  // read the information matrix
38  for(unsigned int i=0; i<_observedPoints*2; i++){
39  // fill the "upper triangle" part of the matrix
40  for(unsigned int j=i; j<_observedPoints*2; j++){
41  is >> information()(i,j);
42  }
43 
44  // fill the lower triangle part
45  for(unsigned int j=0; j<i; j++){
46  information()(i,j) = information()(j,i);
47  }
48 
49  }
50 
51  return true;
52  }
void setSize(int vertices)
EIGEN_STRONG_INLINE const InformationType & information() const
information matrix of the constraint
Definition: base_edge.h:67
unsigned int _observedPoints
void g2o::EdgeSE2LotsOfXY::setDimension ( int  dimension_)
inline

Definition at line 21 of file edge_se2_lotsofxy.h.

22  {
23  _dimension = dimension_;
24  _information.resize(dimension_, dimension_);
25  _error.resize(dimension_, 1);
26  _measurement.resize(dimension_, 1);
27  }
InformationType _information
Definition: base_edge.h:88
bool g2o::EdgeSE2LotsOfXY::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 168 of file edge_se2_lotsofxy.cpp.

References g2o::BaseEdge< D, VectorXD >::_measurement, _observedPoints, g2o::HyperGraph::Edge::_vertices, g2o::BaseVertex< D, T >::estimate(), and g2o::SE2::inverse().

168  {
169  VertexSE2 * pose = static_cast<VertexSE2 *> (_vertices[0]);
170 
171  for(unsigned int i=0; i<_observedPoints; i++){
172  VertexPointXY * xy = static_cast<VertexPointXY *> (_vertices[1+i]);
173  Vector2D m = pose->estimate().inverse() * xy->estimate();
174 
175  unsigned int index = 2*i;
176  _measurement[index] = m[0];
177  _measurement[index+1] = m[1];
178  }
179 
180  return true;
181  }
Eigen::Matrix< double, 2, 1, Eigen::ColMajor > Vector2D
Definition: eigen_types.h:45
unsigned int _observedPoints
VertexContainer _vertices
Definition: hyper_graph.h:202
void g2o::EdgeSE2LotsOfXY::setSize ( int  vertices)
inline

Definition at line 29 of file edge_se2_lotsofxy.h.

Referenced by read().

30  {
34  }
const VertexContainer & vertices() const
Definition: hyper_graph.h:178
void setDimension(int dimension_)
virtual void resize(size_t size)
unsigned int _observedPoints
bool g2o::EdgeSE2LotsOfXY::write ( std::ostream &  os) const
virtual

write the vertex to a stream

Implements g2o::OptimizableGraph::Edge.

Definition at line 54 of file edge_se2_lotsofxy.cpp.

References g2o::BaseEdge< D, VectorXD >::_measurement, _observedPoints, and g2o::BaseEdge< D, VectorXD >::information().

54  {
55  // write number of observed points
56  os << "|| " << _observedPoints;
57 
58  // write measurements
59  for(unsigned int i=0; i<_observedPoints; i++){
60  unsigned int index = 2*i;
61  os << " " << _measurement[index] << " " << _measurement[index+1];
62  }
63 
64  // write information matrix
65  for(unsigned int i=0; i<_observedPoints*2; i++){
66  for(unsigned int j=i; j<_observedPoints*2; j++){
67  os << " " << information()(i,j);
68  }
69  }
70 
71  return os.good();
72  }
EIGEN_STRONG_INLINE const InformationType & information() const
information matrix of the constraint
Definition: base_edge.h:67
unsigned int _observedPoints

Member Data Documentation

unsigned int g2o::EdgeSE2LotsOfXY::_observedPoints
protected
g2o::EdgeSE2LotsOfXY::EIGEN_MAKE_ALIGNED_OPERATOR_NEW

Definition at line 18 of file edge_se2_lotsofxy.h.


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