g2o
Loading...
Searching...
No Matches
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 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
 
virtual bool write (std::ostream &os) const
 write the vertex to a stream
 
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::BaseVariableSizedEdge<-1, VectorX >
 BaseVariableSizedEdge ()
 
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, E >
 BaseEdge ()
 
BaseEdgeoperator= (const BaseEdge &)=delete
 
 BaseEdge (const BaseEdge &)=delete
 
virtual ~BaseEdge ()
 
virtual double chi2 () const
 
virtual const double * errorData () const
 returns the error vector cached after calling the computeError;
 
virtual double * errorData ()
 
const ErrorVectorerror () const
 
ErrorVectorerror ()
 
EIGEN_STRONG_INLINE const InformationTypeinformation () const
 information matrix of the constraint
 
EIGEN_STRONG_INLINE InformationTypeinformation ()
 
void setInformation (const InformationType &information)
 
virtual const double * informationData () const
 
virtual double * informationData ()
 
EIGEN_STRONG_INLINE const Measurementmeasurement () const
 accessor functions for the measurement represented by the edge
 
virtual void setMeasurement (const Measurement &m)
 
virtual int rank () const
 
template<int Dim = D>
std::enable_if< Dim==-1, void >::type setDimension (int dim)
 
- Public Member Functions inherited from g2o::OptimizableGraph::Edge
 Edge ()
 
virtual ~Edge ()
 
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
 
void setRobustKernel (RobustKernel *ptr)
 
int level () const
 returns the level of the edge
 
void setLevel (int l)
 sets the level of the edge
 
int dimension () const
 returns the dimensions of the error function
 
 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
 
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
 
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 ()
 
- Public Member Functions inherited from g2o::HyperGraph::DataContainer
 DataContainer ()
 
virtual ~DataContainer ()
 
const DatauserData () const
 the user data associated with this vertex
 
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::BaseVariableSizedEdge<-1, VectorX >
std::vector< HessianHelper > _hessian
 
std::vector< JacobianType_jacobianOplus
 jacobians of the edge (w.r.t. oplus)
 
- Protected Attributes inherited from g2o::BaseEdge< D, E >
Measurement _measurement
 the measurement of the edge
 
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
 
- Protected Attributes inherited from g2o::HyperGraph::DataContainer
Data_userData
 

Additional Inherited Members

- Public Types inherited from g2o::BaseVariableSizedEdge<-1, VectorX >
typedef BaseEdge< D, VectorX >::Measurement Measurement
 
typedef MatrixX::MapType JacobianType
 
typedef BaseEdge< D, VectorX >::ErrorVector ErrorVector
 
typedef BaseEdge< D, VectorX >::InformationType InformationType
 
typedef Eigen::Map< MatrixX, MatrixX::Flags &Eigen::PacketAccessBit ? Eigen::Aligned :Eigen::Unaligned > HessianBlockType
 
- Public Types inherited from g2o::BaseEdge< D, E >
typedef E Measurement
 
typedef internal::BaseEdgeTraits< D >::ErrorVector ErrorVector
 
typedef internal::BaseEdgeTraits< D >::InformationType InformationType
 
- Static Public Attributes inherited from g2o::BaseVariableSizedEdge<-1, VectorX >
static constexpr int Dimension
 
- Static Public Attributes inherited from g2o::BaseEdge< D, E >
static constexpr int Dimension = internal::BaseEdgeTraits<D>::Dimension
 
- Protected Member Functions inherited from g2o::BaseVariableSizedEdge<-1, VectorX >
void computeQuadraticForm (const InformationType &omega, const ErrorVector &weightedError)
 
- Protected Member Functions inherited from g2o::BaseEdge< D, E >
InformationType robustInformation (const Vector3 &rho) const
 
bool writeInformationMatrix (std::ostream &os) const
 write the upper trinagular part of the information matrix into the stream
 
bool readInformationMatrix (std::istream &is)
 
bool writeParamIds (std::ostream &os) const
 write the param IDs that are potentially used by the edge
 
bool readParamIds (std::istream &is)
 reads the param IDs from the stream
 
- 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 38 of file edge_se2_lotsofxy.h.

Constructor & Destructor Documentation

◆ EdgeSE2LotsOfXY()

g2o::EdgeSE2LotsOfXY::EdgeSE2LotsOfXY ( )

Member Function Documentation

◆ computeError()

void g2o::EdgeSE2LotsOfXY::computeError ( )
virtual

Implements g2o::OptimizableGraph::Edge.

Definition at line 43 of file edge_se2_lotsofxy.cpp.

43 {
44 VertexSE2* pose = static_cast<VertexSE2*>(_vertices[0]);
45
46 for (unsigned int i = 0; i < _observedPoints; i++) {
47 VertexPointXY* xy = static_cast<VertexPointXY*>(_vertices[1 + i]);
48 Vector2 m = pose->estimate().inverse() * xy->estimate();
49
50 unsigned int index = 2 * i;
51 _error[index] = m[0] - _measurement[index];
52 _error[index + 1] = m[1] - _measurement[index + 1];
53 }
54}
Measurement _measurement
the measurement of the edge
Definition base_edge.h:146
ErrorVector _error
Definition base_edge.h:149
VertexContainer _vertices
VectorN< 2 > Vector2
Definition eigen_types.h:50

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

◆ initialEstimate()

void g2o::EdgeSE2LotsOfXY::initialEstimate ( const OptimizableGraph::VertexSet from,
OptimizableGraph::Vertex to 
)
virtual

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

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

Definition at line 144 of file edge_se2_lotsofxy.cpp.

145 {
146 (void)toEstimate;
147
148 assert(initialEstimatePossible(fixed, toEstimate) &&
149 "Bad vertices specified");
150
151 VertexSE2* pose = static_cast<VertexSE2*>(_vertices[0]);
152
153#ifdef _MSC_VER
154 std::vector<bool> estimate_this(_observedPoints, true);
155#else
156 bool estimate_this[_observedPoints];
157 for (unsigned int i = 0; i < _observedPoints; i++) {
158 estimate_this[i] = true;
159 }
160#endif
161
162 for (std::set<HyperGraph::Vertex*>::iterator it = fixed.begin();
163 it != fixed.end(); ++it) {
164 for (unsigned int i = 1; i < _vertices.size(); i++) {
165 VertexPointXY* vert = static_cast<VertexPointXY*>(_vertices[i]);
166 if (vert->id() == (*it)->id()) estimate_this[i - 1] = false;
167 }
168 }
169
170 for (unsigned int i = 1; i < _vertices.size(); i++) {
171 if (estimate_this[i - 1]) {
172 unsigned int index = 2 * (i - 1);
173 Vector2 submeas(_measurement[index], _measurement[index + 1]);
174 VertexPointXY* vert = static_cast<VertexPointXY*>(_vertices[i]);
175 vert->setEstimate(pose->estimate() * submeas);
176 }
177 }
178}
virtual double initialEstimatePossible(const OptimizableGraph::VertexSet &, OptimizableGraph::Vertex *)

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

◆ initialEstimatePossible()

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

182 {
183 (void)toEstimate;
184
185 for (std::set<HyperGraph::Vertex*>::iterator it = fixed.begin();
186 it != fixed.end(); ++it) {
187 if (_vertices[0]->id() == (*it)->id()) {
188 return 1.0;
189 }
190 }
191
192 return -1.0;
193}

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

Referenced by initialEstimate().

◆ linearizeOplus()

void g2o::EdgeSE2LotsOfXY::linearizeOplus ( )
virtual

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

Reimplemented from g2o::BaseVariableSizedEdge<-1, VectorX >.

Definition at line 102 of file edge_se2_lotsofxy.cpp.

102 {
103 const VertexSE2* vi = static_cast<const VertexSE2*>(_vertices[0]);
104 const double& x1 = vi->estimate().translation()[0];
105 const double& y1 = vi->estimate().translation()[1];
106 const double& th1 = vi->estimate().rotation().angle();
107
108 double ct = std::cos(th1);
109 double st = std::sin(th1);
110
111 MatrixX Ji;
112 unsigned int rows = 2 * (_vertices.size() - 1);
113 Ji.resize(rows, 3);
114 Ji.fill(0);
115
116 Matrix2 poseRot; // inverse of the rotation matrix associated to the pose
117 poseRot << ct, st, -st, ct;
118
119 Matrix2 minusPoseRot = -poseRot;
120
121 for (unsigned int i = 1; i < _vertices.size(); i++) {
123
124 const double& x2 = point->estimate()[0];
125 const double& y2 = point->estimate()[1];
126
127 unsigned int index = 2 * (i - 1);
128
129 Ji.block<2, 2>(index, 0) = minusPoseRot;
130
131 Ji(index, 2) = ct * (y2 - y1) + st * (x1 - x2);
132 Ji(index + 1, 2) = st * (y1 - y2) + ct * (x1 - x2);
133
134 MatrixX Jj;
135 Jj.resize(rows, 2);
136 Jj.fill(0);
137 Jj.block<2, 2>(index, 0) = poseRot;
138
139 _jacobianOplus[i] = Jj;
140 }
141 _jacobianOplus[0] = Ji;
142}
std::vector< JacobianType > _jacobianOplus
jacobians of the edge (w.r.t. oplus)
const EstimateType & estimate() const
return the current estimate of the vertex
MatrixN< Eigen::Dynamic > MatrixX
Definition eigen_types.h:74
MatrixN< 2 > Matrix2
Definition eigen_types.h:71

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

◆ read()

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

56 {
57 is >> _observedPoints;
59
60 // read the measurements
61 for (unsigned int i = 0; i < _observedPoints; i++) {
62 unsigned int index = 2 * i;
63 is >> _measurement[index] >> _measurement[index + 1];
64 }
65
66 // read the information matrix
67 for (unsigned int i = 0; i < _observedPoints * 2; i++) {
68 // fill the "upper triangle" part of the matrix
69 for (unsigned int j = i; j < _observedPoints * 2; j++) {
70 is >> information()(i, j);
71 }
72
73 // fill the lower triangle part
74 for (unsigned int j = 0; j < i; j++) {
75 information()(i, j) = information()(j, i);
76 }
77 }
78
79 return true;
80}
EIGEN_STRONG_INLINE const InformationType & information() const
information matrix of the constraint
Definition base_edge.h:107
void setSize(int vertices)

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

◆ setMeasurementFromState()

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

195 {
196 VertexSE2* pose = static_cast<VertexSE2*>(_vertices[0]);
197
198 for (unsigned int i = 0; i < _observedPoints; i++) {
199 VertexPointXY* xy = static_cast<VertexPointXY*>(_vertices[1 + i]);
200 Vector2 m = pose->estimate().inverse() * xy->estimate();
201
202 unsigned int index = 2 * i;
203 _measurement[index] = m[0];
204 _measurement[index + 1] = m[1];
205 }
206
207 return true;
208}

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

◆ setSize()

void g2o::EdgeSE2LotsOfXY::setSize ( int  vertices)
inline

Definition at line 47 of file edge_se2_lotsofxy.h.

47 {
50 _measurement.resize(_observedPoints * 2, 1);
52 }
std::enable_if< Dim==-1, void >::type setDimension(int dim)
Definition base_edge.h:139
const VertexContainer & vertices() const

Referenced by read().

◆ write()

bool g2o::EdgeSE2LotsOfXY::write ( std::ostream &  os) const
virtual

write the vertex to a stream

Implements g2o::OptimizableGraph::Edge.

Definition at line 82 of file edge_se2_lotsofxy.cpp.

82 {
83 // write number of observed points
84 os << "|| " << _observedPoints;
85
86 // write measurements
87 for (unsigned int i = 0; i < _observedPoints; i++) {
88 unsigned int index = 2 * i;
89 os << " " << _measurement[index] << " " << _measurement[index + 1];
90 }
91
92 // write information matrix
93 for (unsigned int i = 0; i < _observedPoints * 2; i++) {
94 for (unsigned int j = i; j < _observedPoints * 2; j++) {
95 os << " " << information()(i, j);
96 }
97 }
98
99 return os.good();
100}

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

Member Data Documentation

◆ _observedPoints

unsigned int g2o::EdgeSE2LotsOfXY::_observedPoints
protected

◆ EIGEN_MAKE_ALIGNED_OPERATOR_NEW

g2o::EdgeSE2LotsOfXY::EIGEN_MAKE_ALIGNED_OPERATOR_NEW

Definition at line 44 of file edge_se2_lotsofxy.h.


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