1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76
|
# ----------------------------------------------------------------------------
# - Open3D: www.open3d.org -
# ----------------------------------------------------------------------------
# The MIT License (MIT)
#
# Copyright (c) 2018-2021 www.open3d.org
#
# Permission is hereby granted, free of charge, to any person obtaining a copy
# of this software and associated documentation files (the "Software"), to deal
# in the Software without restriction, including without limitation the rights
# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
# copies of the Software, and to permit persons to whom the Software is
# furnished to do so, subject to the following conditions:
#
# The above copyright notice and this permission notice shall be included in
# all copies or substantial portions of the Software.
#
# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
# FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
# IN THE SOFTWARE.
# ----------------------------------------------------------------------------
"""Find camera movement between two consecutive RGBD image pairs"""
import open3d as o3d
import numpy as np
if __name__ == "__main__":
pinhole_camera_intrinsic = o3d.camera.PinholeCameraIntrinsic(
o3d.camera.PinholeCameraIntrinsicParameters.PrimeSenseDefault)
rgbd_data = o3d.data.SampleRedwoodRGBDImages()
source_color = o3d.io.read_image(rgbd_data.color_paths[0])
source_depth = o3d.io.read_image(rgbd_data.depth_paths[0])
target_color = o3d.io.read_image(rgbd_data.color_paths[1])
target_depth = o3d.io.read_image(rgbd_data.depth_paths[1])
source_rgbd_image = o3d.geometry.RGBDImage.create_from_color_and_depth(
source_color, source_depth)
target_rgbd_image = o3d.geometry.RGBDImage.create_from_color_and_depth(
target_color, target_depth)
target_pcd = o3d.geometry.PointCloud.create_from_rgbd_image(
target_rgbd_image, pinhole_camera_intrinsic)
option = o3d.pipelines.odometry.OdometryOption()
odo_init = np.identity(4)
print(option)
[success_color_term, trans_color_term,
info] = o3d.pipelines.odometry.compute_rgbd_odometry(
source_rgbd_image, target_rgbd_image,
pinhole_camera_intrinsic, odo_init,
o3d.pipelines.odometry.RGBDOdometryJacobianFromColorTerm(), option)
[success_hybrid_term, trans_hybrid_term,
info] = o3d.pipelines.odometry.compute_rgbd_odometry(
source_rgbd_image, target_rgbd_image,
pinhole_camera_intrinsic, odo_init,
o3d.pipelines.odometry.RGBDOdometryJacobianFromHybridTerm(), option)
if success_color_term:
print("Using RGB-D Odometry")
print(trans_color_term)
source_pcd_color_term = o3d.geometry.PointCloud.create_from_rgbd_image(
source_rgbd_image, pinhole_camera_intrinsic)
source_pcd_color_term.transform(trans_color_term)
o3d.visualization.draw([target_pcd, source_pcd_color_term])
if success_hybrid_term:
print("Using Hybrid RGB-D Odometry")
print(trans_hybrid_term)
source_pcd_hybrid_term = o3d.geometry.PointCloud.create_from_rgbd_image(
source_rgbd_image, pinhole_camera_intrinsic)
source_pcd_hybrid_term.transform(trans_hybrid_term)
o3d.visualization.draw([target_pcd, source_pcd_hybrid_term])
|