|
virtual bool | allVerticesFixed () const |
|
| BaseUnaryEdge () |
|
virtual void | constructQuadraticForm () |
|
virtual void | initialEstimate (const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *to) |
|
const JacobianXiOplusType & | jacobianOplusXi () const |
| returns the result of the linearization in the manifold space for the node xi More...
|
|
virtual void | linearizeOplus (JacobianWorkspace &jacobianWorkspace) |
|
virtual void | linearizeOplus () |
|
virtual void | mapHessianMemory (double *, int, int, bool) |
|
virtual void | resize (size_t size) |
|
| BaseEdge () |
|
virtual double | chi2 () const |
| computes the chi2 based on the cached error value, only valid after computeError has been called. More...
|
|
const ErrorVector & | error () const |
|
ErrorVector & | error () |
|
virtual const double * | errorData () const |
| returns the error vector cached after calling the computeError; More...
|
|
virtual double * | errorData () |
|
const InformationType & | information () const |
| information matrix of the constraint More...
|
|
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 () |
|
const Measurement & | measurement () const |
| accessor functions for the measurement represented by the edge More...
|
|
virtual int | rank () const |
|
void | setInformation (const InformationType &information) |
|
virtual void | setMeasurement (const Measurement &m) |
|
virtual | ~BaseEdge () |
|
virtual Edge * | clone () const |
|
virtual void | computeError ()=0 |
|
virtual Vertex * | createFrom () |
|
virtual Vertex * | createTo () |
|
int | dimension () const |
| returns the dimensions of the error function More...
|
|
| Edge () |
|
virtual bool | getMeasurementData (double *m) const |
|
OptimizableGraph * | graph () |
|
const OptimizableGraph * | graph () const |
|
virtual double | initialEstimatePossible (const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *to) |
|
long long | internalId () const |
| the internal ID of the edge More...
|
|
int | level () const |
| returns the level of the edge More...
|
|
virtual int | measurementDimension () const |
|
size_t | numParameters () const |
|
const Parameter * | parameter (int argNo) const |
|
virtual bool | read (std::istream &is)=0 |
| read the vertex from a stream, i.e., the internal state of the vertex More...
|
|
void | resizeParameters (size_t newSize) |
|
RobustKernel * | robustKernel () const |
| if NOT NULL, error of this edge will be robustifed with the kernel More...
|
|
void | setLevel (int l) |
| sets the level of the edge More...
|
|
virtual bool | setMeasurementData (const double *m) |
|
virtual bool | setMeasurementFromState () |
|
bool | setParameterId (int argNum, int paramId) |
|
void | setRobustKernel (RobustKernel *ptr) |
|
virtual bool | write (std::ostream &os) const =0 |
| write the vertex to a stream More...
|
|
virtual | ~Edge () |
|
| Edge (int id=-1) |
| creates and empty edge with no vertices More...
|
|
virtual HyperGraphElementType | elementType () const |
|
int | id () const |
|
void | setId (int id) |
|
void | setVertex (size_t i, Vertex *v) |
|
const Vertex * | vertex (size_t i) const |
|
Vertex * | vertex (size_t i) |
|
const VertexContainer & | vertices () const |
|
VertexContainer & | vertices () |
|
virtual | ~HyperGraphElement () |
|
template<int D, typename E, typename VertexXi>
class g2o::BaseUnaryEdge< D, E, VertexXi >
Definition at line 43 of file base_unary_edge.h.
template<int D, typename E , typename VertexXiType >
void BaseUnaryEdge::constructQuadraticForm |
( |
| ) |
|
|
virtual |
Linearizes the constraint in the edge. Makes side effect on the vertices of the graph by changing the parameter vector b and the hessian blocks ii and jj. The off diagoinal block is accesed via _hessian.
Implements g2o::OptimizableGraph::Edge.
Definition at line 44 of file base_unary_edge.h.
template<int D, typename E, typename VertexXi>
virtual void g2o::BaseUnaryEdge< D, E, VertexXi >::mapHessianMemory |
( |
double * |
d, |
|
|
int |
i, |
|
|
int |
j, |
|
|
bool |
rowMajor |
|
) |
| |
|
inlinevirtual |
maps the internal matrix to some external memory location, you need to provide the memory before calling constructQuadraticForm
- Parameters
-
d | the memory location to which we map |
i | index of the vertex i |
j | index of the vertex j (j > i, upper triangular fashion) |
rowMajor | if true, will write in rowMajor order to the block. Since EIGEN is columnMajor by default, this results in writing the transposed |
Implements g2o::OptimizableGraph::Edge.
Definition at line 78 of file base_unary_edge.h.