Skip to content

Commit

Permalink
Offline SLAM Small Bug Fix (#5167)
Browse files Browse the repository at this point in the history
  • Loading branch information
yuecideng committed Jun 9, 2022
1 parent 1c725dd commit c8f8f40
Show file tree
Hide file tree
Showing 19 changed files with 74 additions and 69 deletions.
4 changes: 2 additions & 2 deletions cpp/open3d/pipelines/odometry/Odometry.cpp
Expand Up @@ -154,7 +154,7 @@ static CorrespondenceSetPixelWise ComputeCorrespondence(
double d_t = *depth_t.PointerAt<float>(u_t, v_t);
if (!std::isnan(d_t) &&
std::abs(transformed_d_s - d_t) <=
option.max_depth_diff_) {
option.depth_diff_max_) {
AddElementToCorrespondenceMap(
correspondence_map_private,
depth_buffer_private, u_s, v_s, u_t, v_t,
Expand Down Expand Up @@ -321,7 +321,7 @@ static std::shared_ptr<geometry::Image> PreprocessDepth(
for (int y = 0; y < depth_processed->height_; y++) {
for (int x = 0; x < depth_processed->width_; x++) {
float *p = depth_processed->PointerAt<float>(x, y);
if ((*p < option.min_depth_ || *p > option.max_depth_ || *p <= 0))
if ((*p < option.depth_min_ || *p > option.depth_max_ || *p <= 0))
*p = std::numeric_limits<float>::quiet_NaN();
}
}
Expand Down
24 changes: 12 additions & 12 deletions cpp/open3d/pipelines/odometry/OdometryOption.h
Expand Up @@ -41,24 +41,24 @@ class OdometryOption {
///
/// \param iteration_number_per_pyramid_level Number of iterations per level
/// of pyramid.
/// \param max_depth_diff Maximum depth difference to be considered as
/// \param depth_diff_max Maximum depth difference to be considered as
/// correspondence.
/// \param min_depth Minimum depth below which pixel values
/// \param depth_min Minimum depth below which pixel values
/// are ignored.
/// \param max_depth Maximum depth above which pixel values are
/// \param depth_max Maximum depth above which pixel values are
/// ignored.
OdometryOption(
const std::vector<int> &iteration_number_per_pyramid_level =
{20, 10,
5} /* {smaller image size to original image size} */,
double max_depth_diff = 0.03,
double min_depth = 0.0,
double max_depth = 4.0)
double depth_diff_max = 0.03,
double depth_min = 0.0,
double depth_max = 4.0)
: iteration_number_per_pyramid_level_(
iteration_number_per_pyramid_level),
max_depth_diff_(max_depth_diff),
min_depth_(min_depth),
max_depth_(max_depth) {}
depth_diff_max_(depth_diff_max),
depth_min_(depth_min),
depth_max_(depth_max) {}
~OdometryOption() {}

public:
Expand All @@ -69,11 +69,11 @@ class OdometryOption {
/// image domain, if two aligned pixels have a depth difference less than
/// specified value, they are considered as a correspondence. Larger value
/// induce more aggressive search, but it is prone to unstable result.
double max_depth_diff_;
double depth_diff_max_;
/// Pixels that has larger than specified depth values are ignored.
double min_depth_;
double depth_min_;
/// Pixels that has larger than specified depth values are ignored.
double max_depth_;
double depth_max_;
};

} // namespace odometry
Expand Down
28 changes: 14 additions & 14 deletions cpp/pybind/pipelines/odometry/odometry.cpp
Expand Up @@ -67,34 +67,34 @@ void pybind_odometry_classes(py::module &m) {
odometry_option
.def(py::init(
[](std::vector<int> iteration_number_per_pyramid_level,
double max_depth_diff, double min_depth,
double max_depth) {
double depth_diff_max, double depth_min,
double depth_max) {
return new OdometryOption(
iteration_number_per_pyramid_level,
max_depth_diff, min_depth, max_depth);
depth_diff_max, depth_min, depth_max);
}),
"iteration_number_per_pyramid_level"_a =
std::vector<int>{20, 10, 5},
"max_depth_diff"_a = 0.03, "min_depth"_a = 0.0,
"max_depth"_a = 4.0)
"depth_diff_max"_a = 0.03, "depth_min"_a = 0.0,
"depth_max"_a = 4.0)
.def_readwrite("iteration_number_per_pyramid_level",
&OdometryOption::iteration_number_per_pyramid_level_,
"List(int): Iteration number per image pyramid "
"level, typically larger image in the pyramid have "
"lower iteration number to reduce computation "
"time.")
.def_readwrite("max_depth_diff", &OdometryOption::max_depth_diff_,
.def_readwrite("depth_diff_max", &OdometryOption::depth_diff_max_,
"Maximum depth difference to be considered as "
"correspondence. In depth image domain, if two "
"aligned pixels have a depth difference less than "
"specified value, they are considered as a "
"correspondence. Larger value induce more "
"aggressive search, but it is prone to unstable "
"result.")
.def_readwrite("min_depth", &OdometryOption::min_depth_,
.def_readwrite("depth_min", &OdometryOption::depth_min_,
"Pixels that has smaller than specified depth "
"values are ignored.")
.def_readwrite("max_depth", &OdometryOption::max_depth_,
.def_readwrite("depth_max", &OdometryOption::depth_max_,
"Pixels that has larger than specified depth values "
"are ignored.")
.def("__repr__", [](const OdometryOption &c) {
Expand All @@ -112,12 +112,12 @@ void pybind_odometry_classes(py::module &m) {
std::to_string(c.odo_init_) +*/
std::string("\niteration_number_per_pyramid_level = ") +
str_iteration_number_per_pyramid_level_ +
std::string("\nmax_depth_diff = ") +
std::to_string(c.max_depth_diff_) +
std::string("\nmin_depth = ") +
std::to_string(c.min_depth_) +
std::string("\nmax_depth = ") +
std::to_string(c.max_depth_);
std::string("\ndepth_diff_max = ") +
std::to_string(c.depth_diff_max_) +
std::string("\ndepth_min = ") +
std::to_string(c.depth_min_) +
std::string("\ndepth_max = ") +
std::to_string(c.depth_max_);
});

// open3d.odometry.RGBDOdometryJacobian
Expand Down
8 changes: 4 additions & 4 deletions cpp/tests/t/pipelines/slac/SLAC.cpp
Expand Up @@ -213,7 +213,7 @@ TEST_P(SLACPermuteDevices, DISABLED_SLACIntegrate) {
int block_count = 40000;
float voxel_size = 0.05;
float depth_scale = 1000.f;
float max_depth = 3.f;
float depth_max = 3.f;
t::geometry::VoxelBlockGrid voxel_grid(
{"tsdf", "weight", "color"},
{core::Dtype::Float32, core::Dtype::Float32, core::Dtype::Float32},
Expand Down Expand Up @@ -265,14 +265,14 @@ TEST_P(SLACPermuteDevices, DISABLED_SLACIntegrate) {

t::geometry::RGBDImage rgbd_projected =
ctr_grid.Deform(rgbd, intrinsic_t, extrinsic_local_t,
depth_scale, max_depth);
depth_scale, depth_max);
core::Tensor frustum_block_coords =
voxel_grid.GetUniqueBlockCoordinates(
rgbd.depth_, intrinsic_t, extrinsic_t, depth_scale,
max_depth);
depth_max);
voxel_grid.Integrate(frustum_block_coords, rgbd_projected.depth_,
rgbd_projected.color_, intrinsic_t,
extrinsic_t, depth_scale, max_depth);
extrinsic_t, depth_scale, depth_max);
timer.Stop();

++k;
Expand Down
4 changes: 2 additions & 2 deletions docs/jupyter/pipelines/rgbd_odometry.ipynb
Expand Up @@ -137,8 +137,8 @@
"Several parameters in `OdometryOption()`:\n",
"\n",
"- `minimum_correspondence_ratio`: After alignment, measure the overlapping ratio of two RGBD images. If overlapping region of two RGBD image is smaller than specified ratio, the odometry module regards that this is a failure case.\n",
"- `max_depth_diff`: In depth image domain, if two aligned pixels have a depth difference less than specified value, they are considered as a correspondence. Larger value induce more aggressive search, but it is prone to unstable result.\n",
"- `min_depth` and `max_depth`: Pixels that has smaller or larger than specified depth values are ignored."
"- `depth_diff_max`: In depth image domain, if two aligned pixels have a depth difference less than specified value, they are considered as a correspondence. Larger value induce more aggressive search, but it is prone to unstable result.\n",
"- `depth_min` and `depth_max`: Pixels that has smaller or larger than specified depth values are ignored."
]
},
{
Expand Down
4 changes: 2 additions & 2 deletions docs/tutorial/sensor/realsense.rst
Expand Up @@ -112,10 +112,10 @@ The reconstruction result below was obtained with the ``L515_JackJack`` dataset
with the configuration changes::

"path_dataset": "/path/to/downloaded/L515_JackJack.bag"
"max_depth": 0.85,
"depth_max": 0.85,
"tsdf_cubic_size": 0.75,
"voxel_size": 0.025,
"max_depth_diff": 0.03
"depth_diff_max": 0.03

.. raw:: html

Expand Down
4 changes: 2 additions & 2 deletions examples/cpp/AzureKinectMKVReader.cpp
Expand Up @@ -65,9 +65,9 @@ Json::Value GenerateDatasetConfig(const std::string &output_path) {
}

value["name"] = "Azure Kinect Record";
value["max_depth"] = 3.0;
value["depth_max"] = 3.0;
value["voxel_size"] = 0.05;
value["max_depth_diff"] = 0.07;
value["depth_diff_max"] = 0.07;
value["preference_loop_closure_odometry"] = 0.1;
value["preference_loop_closure_registration"] = 5.0;
value["tsdf_cubic_size"] = 3.0;
Expand Down
11 changes: 8 additions & 3 deletions examples/cpp/OfflineSLAM.cpp
Expand Up @@ -41,12 +41,13 @@ void PrintHelp() {
utility::LogInfo(" --intrinsic_path [camera_intrinsic]");
utility::LogInfo(" --voxel_size [=0.0058 (m)]");
utility::LogInfo(" --depth_scale [=1000.0]");
utility::LogInfo(" --max_depth [=3.0]");
utility::LogInfo(" --depth_max [=3.0]");
utility::LogInfo(" --trunc_voxel_multiplier [=8.0]");
utility::LogInfo(" --block_count [=10000]");
utility::LogInfo(" --device [CPU:0]");
utility::LogInfo(" --pointcloud [file path to save the extracted pointcloud]");
utility::LogInfo(" --mesh [file path to save the extracted mesh]");
utility::LogInfo(" --vis [whether to visualize the result]");
utility::LogInfo("To run similar example with a default dataset, try the `OnlineSLAMRGBD` example");
// clang-format on
utility::LogInfo("");
Expand Down Expand Up @@ -209,16 +210,20 @@ int main(int argc, char* argv[]) {
auto pcd = model.ExtractPointCloud();
auto pcd_legacy =
std::make_shared<open3d::geometry::PointCloud>(pcd.ToLegacy());
open3d::visualization::Draw({pcd_legacy}, "Extracted PointCloud.");
open3d::io::WritePointCloud(filename, *pcd_legacy);
if (utility::ProgramOptionExists(argc, argv, "--vis")) {
open3d::visualization::Draw({pcd_legacy}, "Extracted PointCloud.");
}
} else {
// If nothing is specified, draw and save the geometry as mesh.
std::string filename = utility::GetProgramOptionAsString(
argc, argv, "--mesh", "mesh_" + device.ToString() + ".ply");
auto mesh = model.ExtractTriangleMesh();
auto mesh_legacy = std::make_shared<open3d::geometry::TriangleMesh>(
mesh.ToLegacy());
open3d::visualization::Draw({mesh_legacy}, "Extracted Mesh.");
open3d::io::WriteTriangleMesh(filename, *mesh_legacy);
if (utility::ProgramOptionExists(argc, argv, "--vis")) {
open3d::visualization::Draw({mesh_legacy}, "Extracted Mesh.");
}
}
}
4 changes: 2 additions & 2 deletions examples/cpp/RealSenseBagReader.cpp
Expand Up @@ -70,9 +70,9 @@ Json::Value GenerateDatasetConfig(const std::string &output_path,
}

value["name"] = bagfile;
value["max_depth"] = 3.0;
value["depth_max"] = 3.0;
value["voxel_size"] = 0.05;
value["max_depth_diff"] = 0.07;
value["depth_diff_max"] = 0.07;
value["preference_loop_closure_odometry"] = 0.1;
value["preference_loop_closure_registration"] = 5.0;
value["tsdf_cubic_size"] = 3.0;
Expand Down
12 changes: 6 additions & 6 deletions examples/cpp/SLACIntegrate.cpp
Expand Up @@ -45,7 +45,7 @@ void PrintHelp() {
utility::LogInfo(" --intrinsic_path [camera_intrinsic]");
utility::LogInfo(" --block_count [=40000]");
utility::LogInfo(" --depth_scale [=1000.0]");
utility::LogInfo(" --max_depth [=3.0]");
utility::LogInfo(" --depth_max [=3.0]");
utility::LogInfo(" --sdf_trunc [=0.04]");
utility::LogInfo(" --device [CPU:0]");
utility::LogInfo(" --mesh");
Expand Down Expand Up @@ -132,8 +132,8 @@ int main(int argc, char* argv[]) {
argc, argv, "--voxel_size", 3.f / 512.f));
float depth_scale = static_cast<float>(utility::GetProgramOptionAsDouble(
argc, argv, "--depth_scale", 1000.f));
float max_depth = static_cast<float>(
utility::GetProgramOptionAsDouble(argc, argv, "--max_depth", 3.f));
float depth_max = static_cast<float>(
utility::GetProgramOptionAsDouble(argc, argv, "--depth_max", 3.f));
// float sdf_trunc = static_cast<float>(utility::GetProgramOptionAsDouble(
// argc, argv, "--sdf_trunc", 0.04f));
t::geometry::VoxelBlockGrid voxel_grid(
Expand Down Expand Up @@ -176,16 +176,16 @@ int main(int argc, char* argv[]) {

t::geometry::RGBDImage rgbd_projected =
ctr_grid.Deform(rgbd, intrinsic_t, extrinsic_local_t,
depth_scale, max_depth);
depth_scale, depth_max);

core::Tensor frustum_block_coords =
voxel_grid.GetUniqueBlockCoordinates(
rgbd_projected.depth_, intrinsic_t, extrinsic_t,
depth_scale, max_depth);
depth_scale, depth_max);

voxel_grid.Integrate(frustum_block_coords, rgbd_projected.depth_,
rgbd_projected.color_, intrinsic_t,
extrinsic_t, depth_scale, max_depth);
extrinsic_t, depth_scale, depth_max);
timer.Stop();

++k;
Expand Down
2 changes: 1 addition & 1 deletion examples/python/open3d_example.py
Expand Up @@ -214,7 +214,7 @@ def read_rgbd_image(color_file, depth_file, convert_rgb_to_intensity, config):
color,
depth,
depth_scale=config["depth_scale"],
depth_trunc=config["max_depth"],
depth_trunc=config["depth_max"],
convert_rgb_to_intensity=convert_rgb_to_intensity)
return rgbd_image

Expand Down
Expand Up @@ -119,7 +119,7 @@ def main(config, keys):
color,
depth,
depth_scale=config["depth_scale"],
depth_trunc=config["max_depth"],
depth_trunc=config["depth_max"],
convert_rgb_to_intensity=False)
rgbd_images.append(rgbd_image)

Expand All @@ -141,7 +141,7 @@ def main(config, keys):
mesh, camera = o3d.pipelines.color_map.run_non_rigid_optimizer(
mesh, rgbd_images, camera,
o3d.pipelines.color_map.NonRigidOptimizerOption(
maximum_iteration=300, maximum_allowable_depth=config["max_depth"]))
maximum_iteration=300, maximum_allowable_depth=config["depth_max"]))
o3d.visualization.draw_geometries([mesh])
o3d.io.write_triangle_mesh(
os.path.join(path, config["folder_scene"],
Expand Down
4 changes: 2 additions & 2 deletions examples/python/reconstruction_system/config/realsense.json
Expand Up @@ -2,9 +2,9 @@
"name": "Realsense bag file",
"path_dataset": "dataset/realsense.bag",
"path_intrinsic": "optional/read_from_bag_file.json",
"max_depth": 3.0,
"depth_max": 3.0,
"voxel_size": 0.05,
"max_depth_diff": 0.07,
"depth_diff_max": 0.07,
"preference_loop_closure_odometry": 0.1,
"preference_loop_closure_registration": 5.0,
"tsdf_cubic_size": 3.0,
Expand Down
4 changes: 2 additions & 2 deletions examples/python/reconstruction_system/config/tutorial.json
Expand Up @@ -2,9 +2,9 @@
"name": "Open3D reconstruction tutorial http://open3d.org/docs/release/tutorial/reconstruction_system/system_overview.html",
"path_dataset": "dataset/tutorial/",
"path_intrinsic": "",
"max_depth": 3.0,
"depth_max": 3.0,
"voxel_size": 0.05,
"max_depth_diff": 0.07,
"depth_diff_max": 0.07,
"preference_loop_closure_odometry": 0.1,
"preference_loop_closure_registration": 5.0,
"tsdf_cubic_size": 3.0,
Expand Down
12 changes: 6 additions & 6 deletions examples/python/reconstruction_system/data_loader.py
Expand Up @@ -37,9 +37,9 @@ def lounge_data_loader():
config = {}
config['path_dataset'] = lounge_rgbd.extract_dir
config['path_intrinsic'] = ""
config['max_depth'] = 3.0
config['depth_max'] = 3.0
config['voxel_size'] = 0.05
config['max_depth_diff'] = 0.07
config['depth_diff_max'] = 0.07
config['preference_loop_closure_odometry'] = 0.1
config['preference_loop_closure_registration'] = 5.0
config['tsdf_cubic_size'] = 3.0
Expand All @@ -60,9 +60,9 @@ def bedroom_data_loader():
config = {}
config['path_dataset'] = bedroom_rgbd.extract_dir
config['path_intrinsic'] = ""
config['max_depth'] = 3.0
config['depth_max'] = 3.0
config['voxel_size'] = 0.05
config['max_depth_diff'] = 0.07
config['depth_diff_max'] = 0.07
config['preference_loop_closure_odometry'] = 0.1
config['preference_loop_closure_registration'] = 5.0
config['tsdf_cubic_size'] = 3.0
Expand All @@ -83,9 +83,9 @@ def jackjack_data_loader():
config = {}
config['path_dataset'] = jackjack_bag.path
config['path_intrinsic'] = ""
config['max_depth'] = 0.85
config['depth_max'] = 0.85
config['voxel_size'] = 0.025
config['max_depth_diff'] = 0.03
config['depth_diff_max'] = 0.03
config['preference_loop_closure_odometry'] = 0.1
config['preference_loop_closure_registration'] = 5.0
config['tsdf_cubic_size'] = 0.75
Expand Down
8 changes: 4 additions & 4 deletions examples/python/reconstruction_system/initialize_config.py
Expand Up @@ -70,10 +70,10 @@ def initialize_config(config):
set_default_value(config, "depth_map_type", "redwood")
set_default_value(config, "n_frames_per_fragment", 100)
set_default_value(config, "n_keyframes_per_n_frame", 5)
set_default_value(config, "min_depth", 0.3)
set_default_value(config, "max_depth", 3.0)
set_default_value(config, "depth_min", 0.3)
set_default_value(config, "depth_max", 3.0)
set_default_value(config, "voxel_size", 0.05)
set_default_value(config, "max_depth_diff", 0.07)
set_default_value(config, "depth_diff_max", 0.07)
set_default_value(config, "depth_scale", 1000)
set_default_value(config, "preference_loop_closure_odometry", 0.1)
set_default_value(config, "preference_loop_closure_registration", 5.0)
Expand All @@ -83,7 +83,7 @@ def initialize_config(config):
set_default_value(config, "python_multi_threading", True)

# `slac` and `slac_integrate` related parameters.
# `voxel_size` and `min_depth` parameters from previous section,
# `voxel_size` and `depth_min` parameters from previous section,
# are also used in `slac` and `slac_integrate`.
set_default_value(config, "max_iterations", 5)
set_default_value(config, "sdf_trunc", 0.04)
Expand Down

0 comments on commit c8f8f40

Please sign in to comment.