Sim3 Vertex, (x,y,z,qw,qx,qy,qz) the parameterization for the increments constructed is a 7d vector (x,y,z,qx,qy,qz) (note that we leave out the w part of the quaternion. More...
#include <types_seven_dof_expmap.h>
Public Member Functions | |
Vector2d | cam_map1 (const Vector2d &v) const |
Vector2d | cam_map2 (const Vector2d &v) const |
virtual void | oplusImpl (const double *update_) |
virtual bool | read (std::istream &is) |
read the vertex from a stream, i.e., the internal state of the vertex More... | |
virtual void | setToOriginImpl () |
sets the node to the origin (used in the multilevel stuff) More... | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW | VertexSim3Expmap () |
virtual bool | write (std::ostream &os) const |
write the vertex to a stream More... | |
Public Member Functions inherited from g2o::BaseVertex< 7, Sim3 > | |
HessianBlockType & | A () |
return the hessian block associated with the vertex More... | |
const HessianBlockType & | A () const |
virtual const double & | b (int i) const |
get the b vector element More... | |
virtual double & | b (int i) |
Matrix< double, D, 1 > & | b () |
return right hand side b of the constructed linear system More... | |
const Matrix< double, D, 1 > & | b () const |
BaseVertex () | |
virtual double * | bData () |
return a pointer to the b vector associated with this vertex More... | |
virtual void | clearQuadraticForm () |
virtual int | copyB (double *b_) const |
virtual void | discardTop () |
pop the last element from the stack, without restoring the current estimate More... | |
const EstimateType & | estimate () const |
return the current estimate of the vertex More... | |
virtual const double & | hessian (int i, int j) const |
get the element from the hessian matrix More... | |
virtual double & | hessian (int i, int j) |
virtual double * | hessianData () |
virtual double | hessianDeterminant () const |
virtual void | mapHessianMemory (double *d) |
virtual void | pop () |
restore the position of the vertex by retrieving the position from the stack More... | |
virtual void | push () |
backup the position of the vertex to a stack More... | |
void | setEstimate (const EstimateType &et) |
set the estimate for the vertex also calls updateCache() More... | |
virtual double | solveDirect (double lambda=0) |
virtual int | stackSize () const |
return the stack size More... | |
Public Member Functions inherited from g2o::OptimizableGraph::Vertex | |
void | addUserData (Data *obs) |
CacheContainer * | cacheContainer () |
virtual Vertex * | clone () const |
returns a deep copy of the current vertex More... | |
int | colInHessian () const |
get the row of this vertex in the Hessian More... | |
int | dimension () const |
dimension of the estimated state belonging to this node More... | |
virtual int | estimateDimension () const |
bool | fixed () const |
true => this node is fixed during the optimization More... | |
int | G2O_ATTRIBUTE_DEPRECATED (tempIndex() const) |
void | G2O_ATTRIBUTE_DEPRECATED (setTempIndex(int ti)) |
virtual bool | getEstimateData (double *estimate) const |
virtual bool | getEstimateData (std::vector< double > &estimate) const |
virtual bool | getMinimalEstimateData (double *estimate) const |
virtual bool | getMinimalEstimateData (std::vector< double > &estimate) const |
const OptimizableGraph * | graph () const |
OptimizableGraph * | graph () |
int | hessianIndex () const |
temporary index of this node in the parameter vector obtained from linearization More... | |
void | lockQuadraticForm () |
bool | marginalized () const |
true => this node is marginalized out during the optimization More... | |
virtual int | minimalEstimateDimension () const |
void | oplus (const double *v) |
void | setColInHessian (int c) |
set the row of this vertex in the Hessian More... | |
bool | setEstimateData (const double *estimate) |
bool | setEstimateData (const std::vector< double > &estimate) |
void | setFixed (bool fixed) |
true => this node should be considered fixed during the optimization More... | |
void | setHessianIndex (int ti) |
set the temporary index of the vertex in the parameter blocks More... | |
virtual void | setId (int id) |
sets the id of the node in the graph be sure that the graph keeps consistent after changing the id More... | |
void | setMarginalized (bool marginalized) |
true => this node should be marginalized out during the optimization More... | |
bool | setMinimalEstimateData (const double *estimate) |
bool | setMinimalEstimateData (const std::vector< double > &estimate) |
void | setToOrigin () |
sets the node to the origin (used in the multilevel stuff) More... | |
void | setUserData (Data *obs) |
void | unlockQuadraticForm () |
virtual void | updateCache () |
const Data * | userData () const |
the user data associated with this vertex More... | |
Data * | userData () |
Vertex () | |
virtual | ~Vertex () |
Public Member Functions inherited from g2o::HyperGraph::Vertex | |
const EdgeSet & | edges () const |
returns the set of hyper-edges that are leaving/entering in this vertex More... | |
EdgeSet & | edges () |
returns the set of hyper-edges that are leaving/entering in this vertex More... | |
virtual HyperGraphElementType | elementType () const |
int | id () const |
returns the id More... | |
Vertex (int id=-1) | |
creates a vertex having an ID specified by the argument More... | |
Public Member Functions inherited from g2o::HyperGraph::HyperGraphElement | |
virtual | ~HyperGraphElement () |
Public Attributes | |
bool | _fix_scale |
Vector2d | _focal_length1 |
Vector2d | _focal_length2 |
Vector2d | _principle_point1 |
Vector2d | _principle_point2 |
Additional Inherited Members | |
Public Types inherited from g2o::BaseVertex< 7, Sim3 > | |
typedef std::stack< EstimateType, std::vector< EstimateType, Eigen::aligned_allocator< EstimateType > > > | BackupStackType |
typedef Sim3 | EstimateType |
typedef Eigen::Map< Matrix< double, D, D >, Matrix< double, D, D >::Flags &PacketAccessBit?Aligned:Unaligned > | HessianBlockType |
Static Public Attributes inherited from g2o::BaseVertex< 7, Sim3 > | |
static const int | Dimension |
dimension of the estimate (minimal) in the manifold space More... | |
Protected Member Functions inherited from g2o::OptimizableGraph::Vertex | |
virtual bool | setEstimateDataImpl (const double *) |
virtual bool | setMinimalEstimateDataImpl (const double *) |
Protected Attributes inherited from g2o::BaseVertex< 7, Sim3 > | |
Matrix< double, D, 1 > | _b |
BackupStackType | _backup |
EstimateType | _estimate |
HessianBlockType | _hessian |
Protected Attributes inherited from g2o::OptimizableGraph::Vertex | |
CacheContainer * | _cacheContainer |
int | _colInHessian |
int | _dimension |
bool | _fixed |
OptimizableGraph * | _graph |
int | _hessianIndex |
bool | _marginalized |
OpenMPMutex | _quadraticFormMutex |
Data * | _userData |
Protected Attributes inherited from g2o::HyperGraph::Vertex | |
EdgeSet | _edges |
int | _id |
Sim3 Vertex, (x,y,z,qw,qx,qy,qz) the parameterization for the increments constructed is a 7d vector (x,y,z,qx,qy,qz) (note that we leave out the w part of the quaternion.
Definition at line 48 of file types_seven_dof_expmap.h.
g2o::VertexSim3Expmap::VertexSim3Expmap | ( | ) |
Definition at line 31 of file types_seven_dof_expmap.cpp.
|
inline |
Definition at line 74 of file types_seven_dof_expmap.h.
|
inline |
Definition at line 82 of file types_seven_dof_expmap.h.
|
inlinevirtual |
update the position of the node from the parameters in v. Implement in your class!
Implements g2o::OptimizableGraph::Vertex.
Definition at line 60 of file types_seven_dof_expmap.h.
|
virtual |
read the vertex from a stream, i.e., the internal state of the vertex
Implements g2o::OptimizableGraph::Vertex.
Definition at line 44 of file types_seven_dof_expmap.cpp.
|
inlinevirtual |
sets the node to the origin (used in the multilevel stuff)
Implements g2o::OptimizableGraph::Vertex.
Definition at line 56 of file types_seven_dof_expmap.h.
|
virtual |
write the vertex to a stream
Implements g2o::OptimizableGraph::Vertex.
Definition at line 70 of file types_seven_dof_expmap.cpp.
bool g2o::VertexSim3Expmap::_fix_scale |
Definition at line 90 of file types_seven_dof_expmap.h.
Vector2d g2o::VertexSim3Expmap::_focal_length1 |
Definition at line 72 of file types_seven_dof_expmap.h.
Vector2d g2o::VertexSim3Expmap::_focal_length2 |
Definition at line 72 of file types_seven_dof_expmap.h.
Vector2d g2o::VertexSim3Expmap::_principle_point1 |
Definition at line 71 of file types_seven_dof_expmap.h.
Vector2d g2o::VertexSim3Expmap::_principle_point2 |
Definition at line 71 of file types_seven_dof_expmap.h.