|
Graphite
|
Graph class which stores references to vertex and factor descriptors, and provides methods for optimization. More...
#include <graph.hpp>
Public Member Functions | |
| size_t | get_hessian_dimension () const |
| size_t | get_variable_dimension (const size_t block_index) const |
| size_t | get_num_block_columns () const |
| const std::vector< size_t > & | get_offset_vector () const |
| thrust::device_vector< T > & | get_b () |
| std::vector< BaseVertexDescriptor< T, S > * > & | get_vertex_descriptors () |
| std::vector< BaseFactorDescriptor< T, S > * > & | get_factor_descriptors () |
| thrust::device_vector< T > & | get_jacobian_scales () |
| template<typename V > | |
| void | add_vertex_descriptor (V *descriptor) |
| template<typename F > | |
| void | add_factor_descriptor (F *factor) |
| template<typename D > | |
| void | add_descriptor (D *descriptor) |
| bool | initialize_optimization (const uint8_t level) |
| void | deactivate_unused_vertices (const uint8_t level) |
| bool | build_structure () |
| void | compute_error () |
| T | chi2 () |
| void | linearize (StreamPool &streams) |
| void | apply_update (const T *delta_x, StreamPool &streams) |
| void | backup_parameters () |
| void | revert_parameters () |
| void | clear () |
| void | scale_system (const bool enable_scaling) |
Private Attributes | |
| std::vector< BaseVertexDescriptor< T, S > * > | vertex_descriptors |
| std::vector< BaseFactorDescriptor< T, S > * > | factor_descriptors |
| thrust::device_vector< T > | b |
| thrust::device_vector< T > | jacobian_scales |
| size_t | hessian_column |
| std::vector< size_t > | hessian_offsets |
| bool | scale_jacobians |
Graph class which stores references to vertex and factor descriptors, and provides methods for optimization.
| T | Scalar type (e.g., double, float) representing the precision of the vertices and constraints. |
| S | Scalar type (e.g., double, Point2D) representing the precision of the linear system. |