gtsam_points
Loading...
Searching...
No Matches
Public Types | Public Member Functions | List of all members
gtsam_points::NonlinearFactorGPU Class Referenceabstract

Base class for GPU-based nonlinear factors. More...

#include <nonlinear_factor_gpu.hpp>

Inheritance diagram for gtsam_points::NonlinearFactorGPU:
Inheritance graph
[legend]
Collaboration diagram for gtsam_points::NonlinearFactorGPU:
Collaboration graph
[legend]

Public Types

using shared_ptr = gtsam_points::shared_ptr< NonlinearFactorGPU >
 

Public Member Functions

template<typename CONTAINER >
 NonlinearFactorGPU (const CONTAINER &keys)
 
virtual size_t linearization_input_size () const =0
 Size of data to be uploaded to the GPU before linearization.
 
virtual size_t linearization_output_size () const =0
 Size of data to be downloaded from the GPU after linearization.
 
virtual size_t evaluation_input_size () const =0
 Size of data to be uploaded to the GPU before cost evaluation.
 
virtual size_t evaluation_output_size () const =0
 Size of data to be downloaded from the GPU after cost evaluation.
 
virtual void set_linearization_point (const gtsam::Values &values, void *lin_input_cpu)=0
 Write linearization input data to the upload buffer.
 
virtual void issue_linearize (const void *lin_input_cpu, const void *lin_input_gpu, void *lin_output_gpu)=0
 Issue linearization task.
 
virtual void store_linearized (const void *lin_output_cpu)=0
 Read linearization output data from the download buffer.
 
virtual void set_evaluation_point (const gtsam::Values &values, void *eval_input_cpu)=0
 Write cost evaluation input data to the upload buffer.
 
virtual void issue_compute_error (const void *lin_input_cpu, const void *eval_input_cpu, const void *lin_input_gpu, const void *eval_input_gpu, void *eval_output_gpu)=0
 Issue cost evaluation task.
 
virtual void store_computed_error (const void *eval_output_cpu)=0
 Read cost evaluation output data from the download buffer.
 
virtual void sync ()=0
 Perform CPU-GPU synchronization and wait for the task.
 

Detailed Description

Base class for GPU-based nonlinear factors.

Note
To efficiently perform linearization (and cost evaluation) on a GPU, we issue all linearization tasks of GPU-based factors and copy all required data for linearization (e.g., current estimate) at once.

To allow gtsam_points::NonlinearFactorSetGPU to manage linearization, you need to implement the following methods:

For example, implementation for the linearization of the standard ICP factor would be as follows:

Optimizers in gtsam_points calls NonlinearFactorSetGPU's linearization routine before calling linearize() of each factor. You should thus store the linearized factor to a temporary member and just return it when linearize() is called.

Member Function Documentation

◆ evaluation_input_size()

virtual size_t gtsam_points::NonlinearFactorGPU::evaluation_input_size ( ) const
pure virtual

Size of data to be uploaded to the GPU before cost evaluation.

Returns
size_t

Implemented in gtsam_points::IntegratedVGICPFactorGPU.

◆ evaluation_output_size()

virtual size_t gtsam_points::NonlinearFactorGPU::evaluation_output_size ( ) const
pure virtual

Size of data to be downloaded from the GPU after cost evaluation.

Returns
size_t

Implemented in gtsam_points::IntegratedVGICPFactorGPU.

◆ issue_compute_error()

virtual void gtsam_points::NonlinearFactorGPU::issue_compute_error ( const void *  lin_input_cpu,
const void *  eval_input_cpu,
const void *  lin_input_gpu,
const void *  eval_input_gpu,
void *  eval_output_gpu 
)
pure virtual

Issue cost evaluation task.

Parameters
lin_input_cpuLinearization input data on the CPU memory (size == linearization_input_size)
eval_input_cpuCost evaluation input data on the CPU memory (size == evaluation_input_size)
lin_input_gpuLinearization input data on the GPU memory (size == linearization_input_size)
eval_input_gpuCost evaluation input data on the GPU memory (size == evaluation_input_size)
eval_output_gpuOutput data destination on the GPU memory (size == evaluation_output_size)

Implemented in gtsam_points::IntegratedVGICPFactorGPU.

◆ issue_linearize()

virtual void gtsam_points::NonlinearFactorGPU::issue_linearize ( const void *  lin_input_cpu,
const void *  lin_input_gpu,
void *  lin_output_gpu 
)
pure virtual

Issue linearization task.

Parameters
lin_input_cpuLinearization input data on the CPU memory (size == linearization_input_size)
lin_input_gpuLinearization input data on the GPU memory (size == linearization_input_size)
lin_output_gpuOutput data destination on the GPU memory (size == linearization_output_size)

Implemented in gtsam_points::IntegratedVGICPFactorGPU.

◆ linearization_input_size()

virtual size_t gtsam_points::NonlinearFactorGPU::linearization_input_size ( ) const
pure virtual

Size of data to be uploaded to the GPU before linearization.

Returns
size_t

Implemented in gtsam_points::IntegratedVGICPFactorGPU.

◆ linearization_output_size()

virtual size_t gtsam_points::NonlinearFactorGPU::linearization_output_size ( ) const
pure virtual

Size of data to be downloaded from the GPU after linearization.

Returns
size_t

Implemented in gtsam_points::IntegratedVGICPFactorGPU.

◆ set_evaluation_point()

virtual void gtsam_points::NonlinearFactorGPU::set_evaluation_point ( const gtsam::Values &  values,
void *  eval_input_cpu 
)
pure virtual

Write cost evaluation input data to the upload buffer.

Parameters
valuesCurrent estimate
eval_input_cpuData upload buffer (size == evaluation_input_size)

Implemented in gtsam_points::IntegratedVGICPFactorGPU.

◆ set_linearization_point()

virtual void gtsam_points::NonlinearFactorGPU::set_linearization_point ( const gtsam::Values &  values,
void *  lin_input_cpu 
)
pure virtual

Write linearization input data to the upload buffer.

Parameters
valuesCurrent estimate
lin_input_cpuData upload buffer (size == linearization_input_size)

Implemented in gtsam_points::IntegratedVGICPFactorGPU.

◆ store_computed_error()

virtual void gtsam_points::NonlinearFactorGPU::store_computed_error ( const void *  eval_output_cpu)
pure virtual

Read cost evaluation output data from the download buffer.

Parameters
eval_output_cpuData down load buffer (size == evaluation_output_size)

Implemented in gtsam_points::IntegratedVGICPFactorGPU.

◆ store_linearized()

virtual void gtsam_points::NonlinearFactorGPU::store_linearized ( const void *  lin_output_cpu)
pure virtual

Read linearization output data from the download buffer.

Parameters
lin_output_cpuData download buffer (size == linearization_output_size)

Implemented in gtsam_points::IntegratedVGICPFactorGPU.

◆ sync()

virtual void gtsam_points::NonlinearFactorGPU::sync ( )
pure virtual

Perform CPU-GPU synchronization and wait for the task.

Implemented in gtsam_points::IntegratedVGICPFactorGPU.


The documentation for this class was generated from the following file: