Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

introduce gtsam_points/config.hpp #81

Merged
merged 1 commit into from
Oct 1, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 3 additions & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,9 @@ endif()

# GPU-related
if(BUILD_WITH_CUDA)
add_definitions(-DBUILD_GTSAM_POINTS_GPU)
if(NOT GTSAM_POINTS_USE_CUDA)
message(FATAL_ERROR "gtsam_points is not built with CUDA!!")
endif()
set(GPU_SRCS src/glim/odometry/odometry_estimation_gpu.cpp)
endif()

Expand Down
19 changes: 10 additions & 9 deletions src/glim/mapping/global_mapping.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@
#include <gtsam/nonlinear/Values.h>
#include <gtsam/nonlinear/NonlinearFactorGraph.h>

#include <gtsam_points/config.hpp>
#include <gtsam_points/types/point_cloud_cpu.hpp>
#include <gtsam_points/types/point_cloud_gpu.hpp>
#include <gtsam_points/types/gaussian_voxelmap_cpu.hpp>
Expand Down Expand Up @@ -72,7 +73,7 @@ GlobalMappingParams::GlobalMappingParams() {
GlobalMappingParams::~GlobalMappingParams() {}

GlobalMapping::GlobalMapping(const GlobalMappingParams& params) : params(params) {
#ifndef BUILD_GTSAM_POINTS_GPU
#ifndef GTSAM_POINTS_USE_CUDA
if (params.enable_gpu) {
logger->error("GPU-based factors cannot be used because GLIM is built without GPU option!!");
}
Expand All @@ -97,7 +98,7 @@ GlobalMapping::GlobalMapping(const GlobalMappingParams& params) : params(params)
isam2.reset(new gtsam_points::ISAM2ExtDummy(isam2_params));
}

#ifdef BUILD_GTSAM_POINTS_GPU
#ifdef GTSAM_POINTS_USE_CUDA
stream_buffer_roundrobin = std::make_shared<gtsam_points::StreamTempBufferRoundRobin>(64);
#endif

Expand Down Expand Up @@ -233,7 +234,7 @@ void GlobalMapping::insert_submap(int current, const SubMap::Ptr& submap) {
subsampled_submap = gtsam_points::random_sampling(submap->frame, params.randomsampling_rate, mt);
}

#ifdef BUILD_GTSAM_POINTS_GPU
#ifdef GTSAM_POINTS_USE_CUDA
if (params.enable_gpu && !submap->frame->points_gpu) {
submap->frame = gtsam_points::PointCloudGPU::clone(*submap->frame);
}
Expand Down Expand Up @@ -309,7 +310,7 @@ void GlobalMapping::find_overlapping_submaps(double min_overlap) {

if (false) {
}
#ifdef BUILD_GTSAM_POINTS_GPU
#ifdef GTSAM_POINTS_USE_CUDA
else if (std::dynamic_pointer_cast<gtsam_points::GaussianVoxelMapGPU>(submaps[i]->voxelmaps.back()) && subsampled_submaps[j]->points_gpu) {
const auto stream_buffer = std::any_cast<std::shared_ptr<gtsam_points::StreamTempBufferRoundRobin>>(stream_buffer_roundrobin)->get_stream_buffer();
const auto& stream = stream_buffer.first;
Expand Down Expand Up @@ -431,7 +432,7 @@ boost::shared_ptr<gtsam::NonlinearFactorGraph> GlobalMapping::create_matching_co
factors->emplace_shared<gtsam_points::IntegratedVGICPFactor>(X(i), X(current), voxelmap, subsampled_submaps[current]);
}
}
#ifdef BUILD_GTSAM_POINTS_GPU
#ifdef GTSAM_POINTS_USE_CUDA
else if (params.registration_error_factor_type == "VGICP_GPU") {
const auto stream_buffer = std::any_cast<std::shared_ptr<gtsam_points::StreamTempBufferRoundRobin>>(stream_buffer_roundrobin)->get_stream_buffer();
const auto& stream = stream_buffer.first;
Expand Down Expand Up @@ -480,7 +481,7 @@ void GlobalMapping::save(const std::string& path) {

for (const auto& factor : isam2->getFactorsUnsafe()) {
bool serializable = !boost::dynamic_pointer_cast<gtsam_points::IntegratedMatchingCostFactor>(factor)
#ifdef BUILD_GTSAM_POINTS_GPU
#ifdef GTSAM_POINTS_USE_CUDA
&& !boost::dynamic_pointer_cast<gtsam_points::IntegratedVGICPFactorGPU>(factor)
#endif
;
Expand Down Expand Up @@ -513,7 +514,7 @@ void GlobalMapping::save(const std::string& path) {
} else if (boost::dynamic_pointer_cast<gtsam_points::IntegratedVGICPFactor>(factor.second)) {
type = "vgicp";
}
#ifdef BUILD_GTSAM_POINTS_GPU
#ifdef GTSAM_POINTS_USE_CUDA
else if (boost::dynamic_pointer_cast<gtsam_points::IntegratedVGICPFactorGPU>(factor.second)) {
type = "vgicp_gpu";
}
Expand Down Expand Up @@ -612,7 +613,7 @@ bool GlobalMapping::load(const std::string& path) {
subsampled_submaps[i] = subsampled_submap;

if (params.enable_gpu) {
#ifdef BUILD_GTSAM_POINTS_GPU
#ifdef GTSAM_POINTS_USE_CUDA
subsampled_submaps[i] = gtsam_points::PointCloudGPU::clone(*subsampled_submaps[i]);

for (int j = 0; j < params.submap_voxelmap_levels; j++) {
Expand Down Expand Up @@ -662,7 +663,7 @@ bool GlobalMapping::load(const std::string& path) {

if (type == "vgicp" || type == "vgicp_gpu") {
if (params.enable_gpu) {
#ifdef BUILD_GTSAM_POINTS_GPU
#ifdef GTSAM_POINTS_USE_CUDA
const auto stream_buffer = std::any_cast<std::shared_ptr<gtsam_points::StreamTempBufferRoundRobin>>(stream_buffer_roundrobin)->get_stream_buffer();
const auto& stream = stream_buffer.first;
const auto& buffer = stream_buffer.second;
Expand Down
11 changes: 6 additions & 5 deletions src/glim/mapping/sub_mapping.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
#include <gtsam/nonlinear/LinearContainerFactor.h>
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>

#include <gtsam_points/config.hpp>
#include <gtsam_points/types/point_cloud_cpu.hpp>
#include <gtsam_points/types/point_cloud_gpu.hpp>
#include <gtsam_points/types/gaussian_voxelmap_cpu.hpp>
Expand Down Expand Up @@ -81,7 +82,7 @@ SubMapping::SubMapping(const SubMappingParams& params) : params(params) {
values.reset(new gtsam::Values);
graph.reset(new gtsam::NonlinearFactorGraph);

#ifdef BUILD_GTSAM_POINTS_GPU
#ifdef GTSAM_POINTS_USE_CUDA
stream = std::make_shared<gtsam_points::CUDAStream>();
stream_buffer_roundrobin = std::make_shared<gtsam_points::StreamTempBufferRoundRobin>(8);
#endif
Expand Down Expand Up @@ -159,7 +160,7 @@ void SubMapping::insert_frame(const EstimationFrame::ConstPtr& odom_frame_) {
}
}

#ifdef BUILD_GTSAM_POINTS_GPU
#ifdef GTSAM_POINTS_USE_CUDA
if (params.enable_gpu && !odom_frame->frame->points_gpu) {
if (params.enable_gpu) {
auto stream = std::static_pointer_cast<gtsam_points::CUDAStream>(this->stream);
Expand Down Expand Up @@ -289,7 +290,7 @@ void SubMapping::insert_frame(const EstimationFrame::ConstPtr& odom_frame_) {
graph->emplace_shared<gtsam_points::IntegratedVGICPFactor>(X(keyframe_indices[i]), X(current), voxelmap, keyframes.back()->frame);
}
}
#ifdef BUILD_GTSAM_POINTS_GPU
#ifdef GTSAM_POINTS_USE_CUDA
else if (params.registration_error_factor_type == "VGICP_GPU") {
auto roundrobin = std::static_pointer_cast<gtsam_points::StreamTempBufferRoundRobin>(stream_buffer_roundrobin);
auto stream_buffer = roundrobin->get_stream_buffer();
Expand Down Expand Up @@ -379,7 +380,7 @@ void SubMapping::insert_keyframe(const int current, const EstimationFrame::Const
*keyframe = *odom_frame;

if (params.enable_gpu) {
#ifdef BUILD_GTSAM_POINTS_GPU
#ifdef GTSAM_POINTS_USE_CUDA
auto stream = std::static_pointer_cast<gtsam_points::CUDAStream>(this->stream);
keyframe->frame = gtsam_points::PointCloudGPU::clone(*subsampled_frame, *stream);
keyframe->voxelmaps.clear();
Expand Down Expand Up @@ -477,7 +478,7 @@ SubMap::Ptr SubMapping::create_submap(bool force_create) const {
}

// TODO: improve merging process
#ifdef BUILD_GTSAM_POINTS_GPU
#ifdef GTSAM_POINTS_USE_CUDA
if (params.enable_gpu) {
// submap->frame = gtsam_points::merge_frames_gpu(poses_to_merge, keyframes_to_merge, submap_downsample_resolution);
}
Expand Down
3 changes: 2 additions & 1 deletion src/glim/viewer/interactive_viewer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@
#include <gtsam/nonlinear/NonlinearFactor.h>
#include <gtsam/nonlinear/NonlinearFactorGraph.h>

#include <gtsam_points/config.hpp>
#include <gtsam_points/factors/integrated_matching_cost_factor.hpp>
#include <gtsam_points/factors/integrated_vgicp_factor_gpu.hpp>
#include <gtsam_points/optimizers/isam2_result_ext.hpp>
Expand Down Expand Up @@ -452,7 +453,7 @@ void InteractiveViewer::globalmap_on_smoother_update(gtsam_points::ISAM2Ext& isa
if (boost::dynamic_pointer_cast<gtsam_points::IntegratedMatchingCostFactor>(factor)) {
inserted_factors.push_back(std::make_tuple(FactorType::MATCHING_COST, factor->keys()[0], factor->keys()[1]));
}
#ifdef BUILD_GTSAM_POINTS_GPU
#ifdef GTSAM_POINTS_USE_CUDA
if (boost::dynamic_pointer_cast<gtsam_points::IntegratedVGICPFactorGPU>(factor)) {
inserted_factors.push_back(std::make_tuple(FactorType::MATCHING_COST, factor->keys()[0], factor->keys()[1]));
}
Expand Down
3 changes: 2 additions & 1 deletion src/glim/viewer/memory_monitor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
#include <iostream>
#include <glim/util/logging.hpp>
#include <glim/util/extension_module.hpp>
#include <gtsam_points/config.hpp>
#include <gtsam_points/cuda/cuda_memory.hpp>

namespace glim {
Expand Down Expand Up @@ -32,7 +33,7 @@ class MemoryMonitor : public ExtensionModule {
}
last_update_time = now;

#ifdef BUILD_GTSAM_POINTS_GPU
#ifdef GTSAM_POINTS_USE_CUDA
size_t gpu_free = 0;
size_t gpu_total = 0;
gtsam_points::cuda_mem_get_info(&gpu_free, &gpu_total);
Expand Down
3 changes: 2 additions & 1 deletion src/glim/viewer/offline_viewer.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
#include <glim/viewer/offline_viewer.hpp>

#include <gtsam_points/config.hpp>
#include <gtsam_points/optimizers/linearization_hook.hpp>
#include <gtsam_points/cuda/nonlinear_factor_set_gpu_create.hpp>

Expand All @@ -22,7 +23,7 @@ void OfflineViewer::setup_ui() {

progress_modal.reset(new guik::ProgressModal("offline_viewer_progress"));

#ifdef BUILD_GTSAM_POINTS_GPU
#ifdef GTSAM_POINTS_USE_CUDA
gtsam_points::LinearizationHook::register_hook([] { return gtsam_points::create_nonlinear_factor_set_gpu(); });
#endif
}
Expand Down
5 changes: 3 additions & 2 deletions src/glim/viewer/standard_viewer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,12 +4,13 @@

#include <gtsam/inference/Symbol.h>
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam_points/config.hpp>
#include <gtsam_points/factors/integrated_matching_cost_factor.hpp>
#include <gtsam_points/optimizers/isam2_result_ext.hpp>
#include <gtsam_points/optimizers/incremental_fixed_lag_smoother_with_fallback.hpp>
#include <gtsam_points/optimizers/levenberg_marquardt_optimization_status.hpp>

#ifdef BUILD_GTSAM_POINTS_GPU
#ifdef GTSAM_POINTS_USE_CUDA
#include <gtsam_points/factors/integrated_vgicp_factor_gpu.hpp>
#endif

Expand Down Expand Up @@ -283,7 +284,7 @@ void StandardViewer::set_callbacks() {
continue;
}

#ifdef BUILD_GTSAM_POINTS_GPU
#ifdef GTSAM_POINTS_USE_CUDA
const auto gpu_factor = boost::dynamic_pointer_cast<gtsam_points::IntegratedVGICPFactorGPU>(factor);
if (gpu_factor) {
const auto l = [this, idx0](const gtsam::NonlinearFactor* factor) -> std::optional<FactorLine> {
Expand Down
Loading