Skip to content

Commit

Permalink
Log (#16)
Browse files Browse the repository at this point in the history
* new ci

* fix url

* docs for docker

* update README

* odometry logging

* module-wise logging
  • Loading branch information
koide3 authored Jul 11, 2024
1 parent 45aceb4 commit dc14e36
Show file tree
Hide file tree
Showing 29 changed files with 302 additions and 94 deletions.
33 changes: 33 additions & 0 deletions config/config_global_mapping_cpu.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,33 @@
{
/*** GlobalMapping ***
// --- Registration error factors ---
// max_implicit_loop_distance : Maximum distance between submaps for factor creation
// min_implicit_loop_overlap : Overlap threshold for factor creation (smaller = more factors)

// --- Optimizer settings (see https://gtsam.org/doxygen/4.0.0/a03679.html) ---
// use_isam2_dogleg : If true, use dogleg optimizer (robust but slow)
// isam2_relinearize_skip : Relinearization is performed every $isam2_relinearize_skip optimization calls
// isam2_relinearize_thresh : Relinearization is performed only when linear delta gets larger than this
*/
"global_mapping": {
"so_name": "libglobal_mapping.so",
"enable_imu": true,
"enable_optimization": true,
"init_pose_damping_scale": 1e10,
// Relative pose factors
"create_between_factors": true,
"between_registration_type": "GICP",
// Registration error factors
"registration_error_factor_type": "VGICP",
"randomsampling_rate": 0.2,
"submap_voxel_resolution": 0.5,
"submap_voxelmap_levels": 1,
"submap_voxelmap_scaling_factor": 2.0,
"max_implicit_loop_distance": 100.0,
"min_implicit_loop_overlap": 0.2,
// Optimizer settings
"use_isam2_dogleg": false,
"isam2_relinearize_skip": 1,
"isam2_relinearize_thresh": 0.1
}
}
51 changes: 51 additions & 0 deletions config/config_sub_mapping_cpu.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,51 @@
{
/*** SubMapping ***
// enable_imu : If true, create IMU preintegration factors
// enable_optimization : If false, do not submap optimization (use only odom data)

// --- Keyframe management ---
// max_num_keyframes : Maximum number of keyframes in a submap
// keyframe_update_strategy : "DISPLACEMENT" or "OVERLAP"
// keyframe_update_interval_* : Threshold for "DISPLACEMENT" strategy
// max_keyframe_overlap : Threshold for "OVERLAP" strategy

// --- Relative pose factors ---
// create_between_factors : If true, create SE3 relative pose factors between consecutive frames (i.e., odom_factor)
// between_registration_type : Registration factor type for information matrix evaluation of relative pose factors (NONE/GICP)

// --- Registration error factors ---
// registration_error_factor_type : Registration factor type for matching cost minimization (VGICP/VGICP_GPU)
// keyframe_randomsampling_rate : Random sampling rate for registration error factors (1.0 = use all points)
// keyframe_voxel_resolution : Voxel resolution for registration error factors
// keyframe_voxelmap_levels : Multi-resolution voxelmap levels (must be >= 1)
// keyframe_voxelmap_scaling_factor : Multi-resolution voxelmap scaling factor

// --- Post processing ---
// submap_downsample_resolution : Resolution of voxel grid downsampling for created submaps
// submap_voxel_resolution : [deprecated] Resolution of VGICP voxels for created submaps (used in global mapping)
*/
"sub_mapping": {
"so_name": "libsub_mapping.so",
"enable_imu": true,
"enable_optimization": false,
// Keyframe update strategy
"max_num_keyframes": 15,
"keyframe_update_strategy": "OVERLAP",
"keyframe_update_min_points": 500,
"keyframe_update_interval_rot": 3.14,
"keyframe_update_interval_trans": 1.0,
"max_keyframe_overlap": 0.6,
// Relative pose factors
"create_between_factors": false,
"between_registration_type": "GICP",
// Registration error factors
"registration_error_factor_type": "VGICP",
"keyframe_randomsampling_rate": 1.0,
"keyframe_voxel_resolution": 0.25,
"keyframe_voxelmap_levels": 2,
"keyframe_voxelmap_scaling_factor": 2.0,
// Post processing
"submap_downsample_resolution": 0.3,
"submap_voxel_resolution": 0.5
}
}
7 changes: 7 additions & 0 deletions include/glim/mapping/async_global_mapping.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,10 @@
#include <glim/mapping/global_mapping.hpp>
#include <glim/util/concurrent_vector.hpp>

namespace spdlog {
class logger;
}

namespace glim {

/**
Expand Down Expand Up @@ -86,6 +90,9 @@ class AsyncGlobalMapping {

std::mutex global_mapping_mutex;
std::shared_ptr<glim::GlobalMappingBase> global_mapping;

// Logging
std::shared_ptr<spdlog::logger> logger;
};

} // namespace glim
8 changes: 8 additions & 0 deletions include/glim/mapping/global_mapping_base.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,10 @@

#include <glim/mapping/sub_map.hpp>

namespace spdlog {
class logger;
}

namespace glim {

/**
Expand All @@ -14,6 +18,7 @@ namespace glim {
*/
class GlobalMappingBase {
public:
GlobalMappingBase();
virtual ~GlobalMappingBase() {}

/**
Expand Down Expand Up @@ -64,5 +69,8 @@ class GlobalMappingBase {
* @return Loaded global mapping module
*/
static std::shared_ptr<GlobalMappingBase> load_module(const std::string& so_name);

protected:
std::shared_ptr<spdlog::logger> logger;
};
} // namespace glim
9 changes: 9 additions & 0 deletions include/glim/mapping/sub_mapping_base.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,10 @@
#include <glim/odometry/estimation_frame.hpp>
#include <glim/mapping/sub_map.hpp>

namespace spdlog {
class logger;
}

namespace glim {

/**
Expand All @@ -15,6 +19,7 @@ namespace glim {
*/
class SubMappingBase {
public:
SubMappingBase();
virtual ~SubMappingBase() {}

/**
Expand Down Expand Up @@ -56,5 +61,9 @@ class SubMappingBase {
* @return Loaded sub mapping module
*/
static std::shared_ptr<SubMappingBase> load_module(const std::string& so_name);

protected:
// Logging
std::shared_ptr<spdlog::logger> logger;
};
} // namespace glim
7 changes: 7 additions & 0 deletions include/glim/odometry/async_odometry_estimation.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,10 @@
#include <glim/util/concurrent_vector.hpp>
#include <glim/odometry/odometry_estimation_base.hpp>

namespace spdlog {
class logger;
}

namespace glim {

/**
Expand Down Expand Up @@ -85,6 +89,9 @@ class AsyncOdometryEstimation {
bool enable_imu;
std::atomic_int internal_frame_queue_size;
std::shared_ptr<OdometryEstimationBase> odometry_estimation;

// Logging
std::shared_ptr<spdlog::logger> logger;
};

} // namespace glim
9 changes: 9 additions & 0 deletions include/glim/odometry/initial_state_estimation.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,10 @@

#include <glim/odometry/estimation_frame.hpp>

namespace spdlog {
class logger;
}

namespace glim {

/**
Expand All @@ -13,6 +17,7 @@ namespace glim {
*/
class InitialStateEstimation {
public:
InitialStateEstimation();
virtual ~InitialStateEstimation() {}

/**
Expand All @@ -35,6 +40,10 @@ class InitialStateEstimation {
* @return nullptr If it's not ready
*/
virtual EstimationFrame::ConstPtr initial_pose() = 0;

protected:
// Logging
std::shared_ptr<spdlog::logger> logger;
};

/**
Expand Down
9 changes: 9 additions & 0 deletions include/glim/odometry/odometry_estimation_base.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,10 @@
#include <glim/odometry/estimation_frame.hpp>
#include <glim/preprocess/preprocessed_frame.hpp>

namespace spdlog {
class logger;
}

namespace glim {

/**
Expand All @@ -15,6 +19,7 @@ namespace glim {
*/
class OdometryEstimationBase {
public:
OdometryEstimationBase();
virtual ~OdometryEstimationBase() {}

/**
Expand Down Expand Up @@ -57,6 +62,10 @@ class OdometryEstimationBase {
* @return Loaded odometry estimation module
*/
static std::shared_ptr<OdometryEstimationBase> load_module(const std::string& so_name);

protected:
// Logging
std::shared_ptr<spdlog::logger> logger;
};

} // namespace glim
1 change: 1 addition & 0 deletions include/glim/odometry/odometry_estimation_imu.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
#include <boost/shared_ptr.hpp>
#include <glim/odometry/odometry_estimation_base.hpp>


namespace gtsam {
class Pose3;
class Values;
Expand Down
2 changes: 2 additions & 0 deletions include/glim/util/logging.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -11,4 +11,6 @@ void set_default_logger(const std::shared_ptr<spdlog::logger>& logger);

std::shared_ptr<spdlog::sinks::ringbuffer_sink_mt> get_ringbuffer_sink(int buffer_size = 128);

std::shared_ptr<spdlog::logger> create_module_logger(const std::string& module_name);

} // namespace glim
7 changes: 7 additions & 0 deletions include/glim/viewer/interactive_viewer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,10 @@
#include <glim/util/extension_module.hpp>
#include <glim/util/concurrent_vector.hpp>

namespace spdlog {
class logger;
}

namespace gtsam {
class Values;
class NonlinearFactor;
Expand Down Expand Up @@ -112,5 +116,8 @@ class InteractiveViewer : public ExtensionModule {

// Factors to be inserted into the global mapping graph
ConcurrentVector<boost::shared_ptr<gtsam::NonlinearFactor>> new_factors;

// Logging
std::shared_ptr<spdlog::logger> logger;
};
} // namespace glim
7 changes: 7 additions & 0 deletions include/glim/viewer/standard_viewer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,10 @@

#include <glim/util/extension_module.hpp>

namespace spdlog {
class logger;
}

namespace glim {

class TrajectoryManager;
Expand Down Expand Up @@ -71,5 +75,8 @@ class StandardViewer : public ExtensionModule {

std::mutex invoke_queue_mutex;
std::vector<std::function<void()>> invoke_queue;

// Logging
std::shared_ptr<spdlog::logger> logger;
};
}
10 changes: 6 additions & 4 deletions src/glim/mapping/async_global_mapping.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,13 +2,15 @@

#include <spdlog/spdlog.h>

#include <glim/util/logging.hpp>
#include <glim/mapping/callbacks.hpp>

namespace glim {

AsyncGlobalMapping::AsyncGlobalMapping(const std::shared_ptr<glim::GlobalMappingBase>& global_mapping, const int optimization_interval)
: global_mapping(global_mapping),
optimization_interval(optimization_interval) {
optimization_interval(optimization_interval),
logger(create_module_logger("global")) {
request_to_optimize = false;
request_to_find_overlapping_submaps.store(-1.0);

Expand Down Expand Up @@ -55,15 +57,15 @@ int AsyncGlobalMapping::workload() const {
}

void AsyncGlobalMapping::save(const std::string& path) {
spdlog::info("saving to {}...", path);
logger->info("saving to {}...", path);
std::lock_guard<std::mutex> lock(global_mapping_mutex);
global_mapping->save(path);
spdlog::info("saved");
logger->info("saved");
}

std::vector<Eigen::Vector4d> AsyncGlobalMapping::export_points() {
std::lock_guard<std::mutex> lock(global_mapping_mutex);
spdlog::info("exporting points");
logger->info("exporting points");
auto points = global_mapping->export_points();
return points;
}
Expand Down
Loading

0 comments on commit dc14e36

Please sign in to comment.