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

#include <edge_se3_lotsofxyz.h>

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

Public Member Functions

 EdgeSE3LotsOfXYZ ()
 
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_se3_lotsofxyz.h.

Constructor & Destructor Documentation

g2o::EdgeSE3LotsOfXYZ::EdgeSE3LotsOfXYZ ( )

Definition at line 5 of file edge_se3_lotsofxyz.cpp.

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

5  {
6  resize(0);
7  }
virtual void resize(size_t size)

Member Function Documentation

void g2o::EdgeSE3LotsOfXYZ::computeError ( )
virtual

Implements g2o::OptimizableGraph::Edge.

Definition at line 27 of file edge_se3_lotsofxyz.cpp.

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

27  {
28  VertexSE3 * pose = static_cast<VertexSE3 *> (_vertices[0]);
29 
30  for(unsigned int i=0; i<_observedPoints; i++){
31  VertexPointXYZ * xyz = static_cast<VertexPointXYZ *> (_vertices[1+i]);
32  Vector3D m = pose->estimate().inverse() * xyz->estimate();
33 
34  unsigned int index = 3*i;
35  _error[index] = m[0] - _measurement[index];
36  _error[index+1] = m[1] - _measurement[index+1];
37  _error[index+2] = m[2] - _measurement[index+2];
38  }
39  }
Eigen::Matrix< double, 3, 1, Eigen::ColMajor > Vector3D
Definition: eigen_types.h:46
VertexContainer _vertices
Definition: hyper_graph.h:202
void g2o::EdgeSE3LotsOfXYZ::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 135 of file edge_se3_lotsofxyz.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().

135  {
136  (void) toEstimate;
137 
138  assert(initialEstimatePossible(fixed, toEstimate) && "Bad vertices specified");
139 
140  VertexSE3 * pose = static_cast<VertexSE3 *>(_vertices[0]);
141 
142 #ifdef _MSC_VER
143  std::vector<bool> estimate_this(_observedPoints, true);
144 #else
145  bool estimate_this[_observedPoints];
146  for(unsigned int i=0; i<_observedPoints; i++){
147  estimate_this[i] = true;
148  }
149 #endif
150 
151  for(std::set<HyperGraph::Vertex*>::iterator it=fixed.begin(); it!=fixed.end(); it++){
152  for(unsigned int i=1; i<_vertices.size(); i++){
153  VertexPointXYZ * vert = static_cast<VertexPointXYZ *>(_vertices[i]);
154  if(vert->id() == (*it)->id()) estimate_this[i-1] = false;
155  }
156  }
157 
158  for(unsigned int i=1; i<_vertices.size(); i++){
159  if(estimate_this[i-1]){
160  unsigned int index = 3*(i-1);
161  Vector3D submeas(_measurement[index], _measurement[index+1], _measurement[index+2]);
162  VertexPointXYZ * vert = static_cast<VertexPointXYZ *>(_vertices[i]);
163  vert->setEstimate(pose->estimate() * submeas);
164  }
165  }
166  }
Eigen::Matrix< double, 3, 1, Eigen::ColMajor > Vector3D
Definition: eigen_types.h:46
virtual double initialEstimatePossible(const OptimizableGraph::VertexSet &, OptimizableGraph::Vertex *)
VertexContainer _vertices
Definition: hyper_graph.h:202
double g2o::EdgeSE3LotsOfXYZ::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 170 of file edge_se3_lotsofxyz.cpp.

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

Referenced by initialEstimate().

170  {
171  (void) toEstimate;
172 
173  for(std::set<HyperGraph::Vertex *>::iterator it=fixed.begin(); it!=fixed.end(); it++){
174  if(_vertices[0]->id() == (*it)->id()){
175  return 1.0;
176  }
177  }
178 
179  return -1.0;
180  }
VertexContainer _vertices
Definition: hyper_graph.h:202
void g2o::EdgeSE3LotsOfXYZ::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 41 of file edge_se3_lotsofxyz.cpp.

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

41  {
42  g2o::VertexSE3 * pose = (g2o::VertexSE3 *) (_vertices[0]);
43 
44  // initialize Ji matrix
45  MatrixXD Ji;
46  unsigned int rows = 3*(_vertices.size()-1);
47  Ji.resize(rows, 6);
48  Ji.fill(0);
49 
50  Matrix3D poseRot = pose->estimate().inverse().rotation();
51 
52  for(unsigned int i=1; i<_vertices.size(); i++){
54  Vector3D Zcam = pose->estimate().inverse() * point->estimate();
55 
56  unsigned int index=3*(i-1);
57 
58  // Ji.block<3,3>(index,0) = -poseRot;
59  Ji.block<3,3>(index,0) = -Matrix3D::Identity();
60 
61  Ji(index, 3) = -0.0;
62  Ji(index, 4) = -2*Zcam(2);
63  Ji(index, 5) = 2*Zcam(1);
64 
65  Ji(index+1, 3) = 2*Zcam(2);
66  Ji(index+1, 4) = -0.0;
67  Ji(index+1, 5) = -2*Zcam(0);
68 
69  Ji(index+2, 3) = -2*Zcam(1);
70  Ji(index+2, 4) = 2*Zcam(0);
71  Ji(index+2, 5) = -0.0;
72 
73  MatrixXD Jj;
74  Jj.resize(rows, 3);
75  Jj.fill(0);
76  Jj.block<3,3>(index,0) = poseRot;
77 
78  _jacobianOplus[i] = Jj;
79  }
80 
81  _jacobianOplus[0] = Ji;
82 
83  }
Eigen::Matrix< double, 3, 1, Eigen::ColMajor > Vector3D
Definition: eigen_types.h:46
Eigen::Matrix< double, 3, 3, Eigen::ColMajor > Matrix3D
Definition: eigen_types.h:61
Vertex for a tracked point in space.
const EstimateType & estimate() const
return the current estimate of the vertex
Definition: base_vertex.h:99
3D pose Vertex, represented as an Isometry3D
Definition: vertex_se3.h:50
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::EdgeSE3LotsOfXYZ::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 85 of file edge_se3_lotsofxyz.cpp.

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

85  {
86  is >> _observedPoints;
87 
88  setSize(_observedPoints + 1);
89 
90  // read the measurements
91  for(unsigned int i=0; i<_observedPoints; i++){
92  unsigned int index = 3*i;
93  is >> _measurement[index] >> _measurement[index+1] >> _measurement[index+2];
94  }
95 
96  // read the information matrix
97  for(unsigned int i=0; i<_observedPoints*3; i++){
98  // fill the "upper triangle" part of the matrix
99  for(unsigned int j=i; j<_observedPoints*3; j++){
100  is >> information()(i,j);
101  }
102 
103  // fill the lower triangle part
104  for(unsigned int j=0; j<i; j++){
105  information()(i,j) = information()(j,i);
106  }
107 
108  }
109  return true;
110  }
void setSize(int vertices)
EIGEN_STRONG_INLINE const InformationType & information() const
information matrix of the constraint
Definition: base_edge.h:67
void g2o::EdgeSE3LotsOfXYZ::setDimension ( int  dimension_)
inline

Definition at line 21 of file edge_se3_lotsofxyz.h.

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

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

9  {
10  VertexSE3 * pose = static_cast<VertexSE3 *> (_vertices[0]);
11 
12  Eigen::Transform<double, 3, 1> poseinv = pose->estimate().inverse();
13 
14  for(unsigned int i=0; i<_observedPoints; i++){
15  VertexPointXYZ * xyz = static_cast<VertexPointXYZ *> (_vertices[1+i]);
16  // const Vector3D &pt = xyz->estimate();
17  Vector3D m = poseinv * xyz->estimate();
18 
19  unsigned int index = 3*i;
20  _measurement[index] = m[0];
21  _measurement[index+1] = m[1];
22  _measurement[index+2] = m[2];
23  }
24  return true;
25  }
Eigen::Matrix< double, 3, 1, Eigen::ColMajor > Vector3D
Definition: eigen_types.h:46
VertexContainer _vertices
Definition: hyper_graph.h:202
void g2o::EdgeSE3LotsOfXYZ::setSize ( int  vertices)
inline

Definition at line 28 of file edge_se3_lotsofxyz.h.

Referenced by read().

28  {
32  }
const VertexContainer & vertices() const
Definition: hyper_graph.h:178
void setDimension(int dimension_)
virtual void resize(size_t size)
bool g2o::EdgeSE3LotsOfXYZ::write ( std::ostream &  os) const
virtual

write the vertex to a stream

Implements g2o::OptimizableGraph::Edge.

Definition at line 114 of file edge_se3_lotsofxyz.cpp.

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

114  {
115  // write number of observed points
116  os << "|| " << _observedPoints;
117 
118  // write measurements
119  for(unsigned int i=0; i<_observedPoints; i++){
120  unsigned int index = 3*i;
121  os << " " << _measurement[index] << " " << _measurement[index+1] << " " << _measurement[index+2];
122  }
123 
124  // write information matrix
125  for(unsigned int i=0; i<_observedPoints*3; i++){
126  for(unsigned int j=i; j<_observedPoints*3; j++){
127  os << " " << information()(i,j);
128  }
129  }
130  return os.good();
131  }
EIGEN_STRONG_INLINE const InformationType & information() const
information matrix of the constraint
Definition: base_edge.h:67

Member Data Documentation

unsigned int g2o::EdgeSE3LotsOfXYZ::_observedPoints
protected
g2o::EdgeSE3LotsOfXYZ::EIGEN_MAKE_ALIGNED_OPERATOR_NEW

Definition at line 18 of file edge_se3_lotsofxyz.h.


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