gtsam_points
Loading...
Searching...
No Matches
nonlinear_factor_gpu.hpp
1// SPDX-License-Identifier: MIT
2// Copyright (c) 2021 Kenji Koide (k.koide@aist.go.jp)
3
4#pragma once
5
6#include <boost/utility/in_place_factory.hpp>
7#include <boost/utility/typed_in_place_factory.hpp>
8#include <gtsam/nonlinear/NonlinearFactor.h>
9#include <gtsam_points/util/gtsam_migration.hpp>
10
11namespace gtsam_points {
12
37class NonlinearFactorGPU : public gtsam::NonlinearFactor {
38public:
39 using shared_ptr = gtsam_points::shared_ptr<NonlinearFactorGPU>;
40
41 template <typename CONTAINER>
42 NonlinearFactorGPU(const CONTAINER& keys) : gtsam::NonlinearFactor(keys) {}
43 virtual ~NonlinearFactorGPU() {}
44
49 virtual size_t linearization_input_size() const = 0;
50
55 virtual size_t linearization_output_size() const = 0;
56
61 virtual size_t evaluation_input_size() const = 0;
62
67 virtual size_t evaluation_output_size() const = 0;
68
74 virtual void set_linearization_point(const gtsam::Values& values, void* lin_input_cpu) = 0;
75
82 virtual void issue_linearize(const void* lin_input_cpu, const void* lin_input_gpu, void* lin_output_gpu) = 0;
83
88 virtual void store_linearized(const void* lin_output_cpu) = 0;
89
95 virtual void set_evaluation_point(const gtsam::Values& values, void* eval_input_cpu) = 0;
96
106 const void* lin_input_cpu,
107 const void* eval_input_cpu,
108 const void* lin_input_gpu,
109 const void* eval_input_gpu,
110 void* eval_output_gpu) = 0;
111
116 virtual void store_computed_error(const void* eval_output_cpu) = 0;
117
121 virtual void sync() = 0;
122};
123
124} // namespace gtsam_points
Base class for GPU-based nonlinear factors.
Definition nonlinear_factor_gpu.hpp:37
virtual size_t evaluation_input_size() const =0
Size of data to be uploaded to the GPU before cost evaluation.
virtual size_t linearization_input_size() const =0
Size of data to be uploaded to the GPU before linearization.
virtual void store_computed_error(const void *eval_output_cpu)=0
Read cost evaluation output data from the download buffer.
virtual void set_linearization_point(const gtsam::Values &values, void *lin_input_cpu)=0
Write linearization input data to the upload 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 size_t linearization_output_size() const =0
Size of data to be downloaded from the GPU after linearization.
virtual size_t evaluation_output_size() const =0
Size of data to be downloaded from the GPU after cost evaluation.
virtual void sync()=0
Perform CPU-GPU synchronization and wait for the task.
virtual void issue_linearize(const void *lin_input_cpu, const void *lin_input_gpu, void *lin_output_gpu)=0
Issue linearization task.
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_linearized(const void *lin_output_cpu)=0
Read linearization output data from the download buffer.