This class holds a set of GPU-based NonlinearFactors and manages their linearization and cost evaluation tasks.
More...
#include <nonlinear_factor_set_gpu.hpp>
|
| int | size () const override |
| | Number of GPU factors in this set.
|
| |
|
void | clear () override |
| | Remove all factors.
|
| |
|
void | clear_counts () override |
| | Reset linearization and cost evaluation counts.
|
| |
| int | linearization_count () const override |
| | Number of issued linearization tasks.
|
| |
| int | evaluation_count () const override |
| | Number of issued cost evaluation tasks.
|
| |
| bool | add (gtsam::NonlinearFactor::shared_ptr factor) override |
| | Add a factor to the GPU factor set if it is a GPU-based one.
|
| |
| void | add (const gtsam::NonlinearFactorGraph &factors) override |
| | Add all GPU-based factors in a factor graph to the GPU factor set.
|
| |
| void | linearize (const gtsam::Values &linearization_point) override |
| | Compute all GPU-based linearization tasks.
|
| |
| void | error (const gtsam::Values &values) override |
| | Compute all GPU-based cost evaluation tasks.
|
| |
| std::vector< gtsam::GaussianFactor::shared_ptr > | calc_linear_factors (const gtsam::Values &linearization_point) override |
| | Calculate linearized factors.
|
| |
This class holds a set of GPU-based NonlinearFactors and manages their linearization and cost evaluation tasks.
◆ add() [1/2]
| void gtsam_points::NonlinearFactorSetGPU::add |
( |
const gtsam::NonlinearFactorGraph & |
factors | ) |
|
|
override |
Add all GPU-based factors in a factor graph to the GPU factor set.
- Parameters
-
◆ add() [2/2]
| bool gtsam_points::NonlinearFactorSetGPU::add |
( |
gtsam::NonlinearFactor::shared_ptr |
factor | ) |
|
|
override |
Add a factor to the GPU factor set if it is a GPU-based one.
- Parameters
-
- Returns
- True if the factor is GPU-based one and added to the set
◆ calc_linear_factors()
| std::vector< gtsam::GaussianFactor::shared_ptr > gtsam_points::NonlinearFactorSetGPU::calc_linear_factors |
( |
const gtsam::Values & |
linearization_point | ) |
|
|
override |
Calculate linearized factors.
- Parameters
-
| linearization_point | Current estimated |
- Returns
- Linearized factors
◆ error()
| void gtsam_points::NonlinearFactorSetGPU::error |
( |
const gtsam::Values & |
values | ) |
|
|
override |
Compute all GPU-based cost evaluation tasks.
- Parameters
-
◆ evaluation_count()
| int gtsam_points::NonlinearFactorSetGPU::evaluation_count |
( |
| ) |
const |
|
inlineoverride |
Number of issued cost evaluation tasks.
- Returns
- int
◆ linearization_count()
| int gtsam_points::NonlinearFactorSetGPU::linearization_count |
( |
| ) |
const |
|
inlineoverride |
Number of issued linearization tasks.
- Returns
- int
◆ linearize()
| void gtsam_points::NonlinearFactorSetGPU::linearize |
( |
const gtsam::Values & |
linearization_point | ) |
|
|
override |
Compute all GPU-based linearization tasks.
- Parameters
-
| linearization_point | Current estimate |
◆ size()
| int gtsam_points::NonlinearFactorSetGPU::size |
( |
| ) |
const |
|
inlineoverride |
Number of GPU factors in this set.
- Returns
- Number of GPU factors in this set
The documentation for this class was generated from the following file: