provide memory workspace for computing the Jacobians More...
#include <jacobian_workspace.h>
Public Types | |
typedef std::vector< Eigen::VectorXd, Eigen::aligned_allocator< Eigen::VectorXd > > | WorkspaceVector |
Public Member Functions | |
bool | allocate () |
JacobianWorkspace () | |
void | updateSize (const HyperGraph::Edge *e) |
void | updateSize (const OptimizableGraph &graph) |
void | updateSize (int numVertices, int dimension) |
double * | workspaceForVertex (int vertexIndex) |
~JacobianWorkspace () | |
Protected Attributes | |
int | _maxDimension |
the maximum dimension (number of elements) for a Jacobian More... | |
int | _maxNumVertices |
the maximum number of vertices connected by a hyper-edge More... | |
WorkspaceVector | _workspace |
the memory pre-allocated for computing the Jacobians More... | |
provide memory workspace for computing the Jacobians
The workspace is used by an OptimizableGraph to provide temporary memory for computing the Jacobian of the error functions. Before calling linearizeOplus on an edge, the workspace needs to be allocated by calling allocate().
Definition at line 50 of file jacobian_workspace.h.
typedef std::vector<Eigen::VectorXd, Eigen::aligned_allocator<Eigen::VectorXd> > g2o::JacobianWorkspace::WorkspaceVector |
Definition at line 53 of file jacobian_workspace.h.
g2o::JacobianWorkspace::JacobianWorkspace | ( | ) |
Definition at line 37 of file jacobian_workspace.cpp.
g2o::JacobianWorkspace::~JacobianWorkspace | ( | ) |
Definition at line 42 of file jacobian_workspace.cpp.
bool g2o::JacobianWorkspace::allocate | ( | ) |
allocate the workspace
Definition at line 46 of file jacobian_workspace.cpp.
void g2o::JacobianWorkspace::updateSize | ( | const HyperGraph::Edge * | e | ) |
update the maximum required workspace needed by taking into account this edge
Definition at line 59 of file jacobian_workspace.cpp.
void g2o::JacobianWorkspace::updateSize | ( | const OptimizableGraph & | graph | ) |
update the required workspace by looking at a full graph
Definition at line 75 of file jacobian_workspace.cpp.
void g2o::JacobianWorkspace::updateSize | ( | int | numVertices, |
int | dimension | ||
) |
manually update with the given parameters
Definition at line 83 of file jacobian_workspace.cpp.
|
inline |
return the workspace for a vertex in an edge
Definition at line 82 of file jacobian_workspace.h.
|
protected |
the maximum dimension (number of elements) for a Jacobian
Definition at line 91 of file jacobian_workspace.h.
|
protected |
the maximum number of vertices connected by a hyper-edge
Definition at line 90 of file jacobian_workspace.h.
|
protected |
the memory pre-allocated for computing the Jacobians
Definition at line 89 of file jacobian_workspace.h.