g2o
Loading...
Searching...
No Matches
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 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_se3_lotsofxyz.h.

Constructor & Destructor Documentation

◆ EdgeSE3LotsOfXYZ()

g2o::EdgeSE3LotsOfXYZ::EdgeSE3LotsOfXYZ ( )

Member Function Documentation

◆ computeError()

void g2o::EdgeSE3LotsOfXYZ::computeError ( )
virtual

Implements g2o::OptimizableGraph::Edge.

Definition at line 56 of file edge_se3_lotsofxyz.cpp.

56 {
57 VertexSE3* pose = static_cast<VertexSE3*>(_vertices[0]);
58
59 for (unsigned int i = 0; i < _observedPoints; i++) {
60 VertexPointXYZ* xyz = static_cast<VertexPointXYZ*>(_vertices[1 + i]);
61 Vector3 m = pose->estimate().inverse() * xyz->estimate();
62
63 unsigned int index = 3 * i;
64 _error[index] = m[0] - _measurement[index];
65 _error[index + 1] = m[1] - _measurement[index + 1];
66 _error[index + 2] = m[2] - _measurement[index + 2];
67 }
68}
Measurement _measurement
the measurement of the edge
Definition base_edge.h:146
ErrorVector _error
Definition base_edge.h:149
VertexContainer _vertices
VectorN< 3 > Vector3
Definition eigen_types.h:51

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

◆ initialEstimate()

void g2o::EdgeSE3LotsOfXYZ::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 160 of file edge_se3_lotsofxyz.cpp.

161 {
162 (void)toEstimate;
163
164 assert(initialEstimatePossible(fixed, toEstimate) &&
165 "Bad vertices specified");
166
167 VertexSE3* pose = static_cast<VertexSE3*>(_vertices[0]);
168
169#ifdef _MSC_VER
170 std::vector<bool> estimate_this(_observedPoints, true);
171#else
172 bool estimate_this[_observedPoints];
173 for (unsigned int i = 0; i < _observedPoints; i++) {
174 estimate_this[i] = true;
175 }
176#endif
177
178 for (std::set<HyperGraph::Vertex*>::iterator it = fixed.begin();
179 it != fixed.end(); ++it) {
180 for (unsigned int i = 1; i < _vertices.size(); i++) {
181 VertexPointXYZ* vert = static_cast<VertexPointXYZ*>(_vertices[i]);
182 if (vert->id() == (*it)->id()) estimate_this[i - 1] = false;
183 }
184 }
185
186 for (unsigned int i = 1; i < _vertices.size(); i++) {
187 if (estimate_this[i - 1]) {
188 unsigned int index = 3 * (i - 1);
189 Vector3 submeas(_measurement[index], _measurement[index + 1],
190 _measurement[index + 2]);
191 VertexPointXYZ* vert = static_cast<VertexPointXYZ*>(_vertices[i]);
192 vert->setEstimate(pose->estimate() * submeas);
193 }
194 }
195}
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::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 197 of file edge_se3_lotsofxyz.cpp.

199 {
200 (void)toEstimate;
201
202 for (std::set<HyperGraph::Vertex*>::iterator it = fixed.begin();
203 it != fixed.end(); ++it) {
204 if (_vertices[0]->id() == (*it)->id()) {
205 return 1.0;
206 }
207 }
208
209 return -1.0;
210}

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

Referenced by initialEstimate().

◆ linearizeOplus()

void g2o::EdgeSE3LotsOfXYZ::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 70 of file edge_se3_lotsofxyz.cpp.

70 {
72
73 // initialize Ji matrix
74 MatrixX Ji;
75 unsigned int rows = 3 * (_vertices.size() - 1);
76 Ji.resize(rows, 6);
77 Ji.fill(0);
78
79 Matrix3 poseRot = pose->estimate().inverse().rotation();
80
81 for (unsigned int i = 1; i < _vertices.size(); i++) {
83 Vector3 Zcam = pose->estimate().inverse() * point->estimate();
84
85 unsigned int index = 3 * (i - 1);
86
87 // Ji.block<3,3>(index,0) = -poseRot;
88 Ji.block<3, 3>(index, 0) = -Matrix3::Identity();
89
90 Ji(index, 3) = -0.0;
91 Ji(index, 4) = -2 * Zcam(2);
92 Ji(index, 5) = 2 * Zcam(1);
93
94 Ji(index + 1, 3) = 2 * Zcam(2);
95 Ji(index + 1, 4) = -0.0;
96 Ji(index + 1, 5) = -2 * Zcam(0);
97
98 Ji(index + 2, 3) = -2 * Zcam(1);
99 Ji(index + 2, 4) = 2 * Zcam(0);
100 Ji(index + 2, 5) = -0.0;
101
102 MatrixX Jj;
103 Jj.resize(rows, 3);
104 Jj.fill(0);
105 Jj.block<3, 3>(index, 0) = poseRot;
106
107 _jacobianOplus[i] = Jj;
108 }
109
110 _jacobianOplus[0] = Ji;
111}
std::vector< JacobianType > _jacobianOplus
jacobians of the edge (w.r.t. oplus)
const EstimateType & estimate() const
return the current estimate of the vertex
Vertex for a tracked point in space.
3D pose Vertex, represented as an Isometry3
Definition vertex_se3.h:50
MatrixN< Eigen::Dynamic > MatrixX
Definition eigen_types.h:74
MatrixN< 3 > Matrix3
Definition eigen_types.h:72

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

◆ read()

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 113 of file edge_se3_lotsofxyz.cpp.

113 {
114 is >> _observedPoints;
115
117
118 // read the measurements
119 for (unsigned int i = 0; i < _observedPoints; i++) {
120 unsigned int index = 3 * i;
121 is >> _measurement[index] >> _measurement[index + 1] >>
122 _measurement[index + 2];
123 }
124
125 // read the information matrix
126 for (unsigned int i = 0; i < _observedPoints * 3; i++) {
127 // fill the "upper triangle" part of the matrix
128 for (unsigned int j = i; j < _observedPoints * 3; j++) {
129 is >> information()(i, j);
130 }
131
132 // fill the lower triangle part
133 for (unsigned int j = 0; j < i; j++) {
134 information()(i, j) = information()(j, i);
135 }
136 }
137 return true;
138}
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::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 38 of file edge_se3_lotsofxyz.cpp.

38 {
39 VertexSE3* pose = static_cast<VertexSE3*>(_vertices[0]);
40
41 Eigen::Transform<double, 3, 1> poseinv = pose->estimate().inverse();
42
43 for (unsigned int i = 0; i < _observedPoints; i++) {
44 VertexPointXYZ* xyz = static_cast<VertexPointXYZ*>(_vertices[1 + i]);
45 // const Vector3 &pt = xyz->estimate();
46 Vector3 m = poseinv * xyz->estimate();
47
48 unsigned int index = 3 * i;
49 _measurement[index] = m[0];
50 _measurement[index + 1] = m[1];
51 _measurement[index + 2] = m[2];
52 }
53 return true;
54}

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

◆ setSize()

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

Definition at line 47 of file edge_se3_lotsofxyz.h.

47 {
50 _measurement.resize(_observedPoints * 3, 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::EdgeSE3LotsOfXYZ::write ( std::ostream &  os) const
virtual

write the vertex to a stream

Implements g2o::OptimizableGraph::Edge.

Definition at line 140 of file edge_se3_lotsofxyz.cpp.

140 {
141 // write number of observed points
142 os << "|| " << _observedPoints;
143
144 // write measurements
145 for (unsigned int i = 0; i < _observedPoints; i++) {
146 unsigned int index = 3 * i;
147 os << " " << _measurement[index] << " " << _measurement[index + 1] << " "
148 << _measurement[index + 2];
149 }
150
151 // write information matrix
152 for (unsigned int i = 0; i < _observedPoints * 3; i++) {
153 for (unsigned int j = i; j < _observedPoints * 3; j++) {
154 os << " " << information()(i, j);
155 }
156 }
157 return os.good();
158}

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

Member Data Documentation

◆ _observedPoints

unsigned int g2o::EdgeSE3LotsOfXYZ::_observedPoints
protected

◆ EIGEN_MAKE_ALIGNED_OPERATOR_NEW

g2o::EdgeSE3LotsOfXYZ::EIGEN_MAKE_ALIGNED_OPERATOR_NEW

Definition at line 44 of file edge_se3_lotsofxyz.h.


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