📖
Wiki
Back to my personal website
  • Home
  • Equipment and Devices
    • 3D Printer
    • Laser Cutter
    • Motion Capture System
    • Sensors
      • RGB-D Cameras
      • Velodyne LiDAR
      • Zed Camera
      • RealSense D435i
      • IMU
    • eGPU
    • Nvidia AGX Xavier
    • CPU Benchmark
    • Installation Checklist
  • Development
    • Linux
      • Shell
      • GDB
      • Git
      • Tmux
      • Network
      • Tricks
      • Debug FAQ
    • CMake
      • Catkin Tools
      • CMakeLists
      • CMake Variables
      • CMake Commands
      • CMake: find_package()
    • ROS
      • Gazebo
      • wstool
      • roslaunch
      • rosbag
      • multi-threaded spinner
    • ROS2
      • Convert ROS1 bag to ROS2 bag
    • C++
      • C++ 11
      • C++ Examples
      • C++ Debug
      • Factory Method
      • Timing
    • Google Tools
      • GLog
      • GFlags
      • GTest
      • Style Guide
      • Clang Format
    • PCL
      • Point Type
      • Methods
      • Architecture
      • Code Explained
    • Open3D
      • Python API
      • Registration
      • Visualization
      • Tools
    • OpenCV
      • Documentation
      • Modules
    • Other Libraries
      • Eigen
      • Ceres
      • g2o
      • GTSAM
    • Website
  • Algorithm
    • SLAM
      • K-D Tree
      • Octree
      • Bag of Words
      • Distance Measures
      • Coordinate Systems
      • LOAM
      • Iterative Closest Point
      • Generalized ICP
      • Mahalanobis Distance
    • Computer Science
      • Computational Model
      • Sorting
      • Analysis
      • Complexity Classes (P, NP)
      • Divide and Conquer
      • Greedy Algorithm
      • Dynamic Programming
      • Tree
      • Graph
    • Computer Vision
      • Camera Models
      • Distortion
      • Motion Models
      • Shutter
      • Image Sensors
      • Epipolar Geometry
      • Multiple-View Geometry
    • Datasets
      • RGB-D Datasets
      • Point Cloud Datasets
      • LiDAR SLAM Datasets
  • Math
    • Optimization
      • Convex Optimization
      • Descent Methods
    • Probability
      • Moment
      • Covariance Matrix
      • Stochastic Process
    • Topology
      • References
      • Concepts
      • Topological Spaces
      • Representation of Rotations
      • Representation of 3-sphere
    • Algebra
      • Linear Algebra
      • Matrix Factorization
      • Condition Number
      • Matrix Lie Group
    • Differential Geometry
      • Manifold
      • Submanifold
      • Quotient Manifolds
      • Tangent Space
  • Quadrotor
    • PX4 Development
    • Companion Computer
    • Drone Hardware
    • Propeller Lock
    • Debug
  • Favorites
    • Bookmarks
Powered by GitBook
On this page
  • PCD Viewer
  • Keypoint Viewer
  • Crop Polygon
  • Crop Selected Sphere
  • Keypoint Animation
  • References

Was this helpful?

  1. Development
  2. Open3D

Visualization

PCD Viewer

#!/usr/bin/env python3
import sys
import open3d as o3d

if __name__ == "__main__":
    pcd = o3d.io.read_point_cloud(sys.argv[1])
    o3d.visualization.draw_geometries([pcd])

Keypoint Viewer

#!/usr/bin/env python3
import os
import open3d as o3d

def keypoints_to_spheres(keypoints):
    spheres = o3d.geometry.TriangleMesh()
    for keypoint in keypoints.points:
        sphere = o3d.geometry.TriangleMesh.create_sphere(radius=0.01)
        sphere.translate(keypoint)
        spheres += sphere
    spheres.paint_uniform_color([1.0, 0.0, 0.0])
    return spheres

if __name__ == "__main__":
    os.system('../build/test_keypoint ../config/params.yaml')
    cloud = o3d.io.read_point_cloud("../data/cloud.pcd")
    keypoints = o3d.io.read_point_cloud("../data/keypoint.pcd")
    o3d.visualization.draw_geometries([cloud, keypoints_to_spheres(keypoints)])

Crop Polygon

#!/usr/bin/env python3
import sys
import open3d as o3d

if __name__ == "__main__":
    print("Demo for manual geometry cropping")
    print("1) Press 'Y' twice to align geometry with negative direction of y-axis")
    print("2) Press 'K' to lock screen and to switch to selection mode")
    print("3) Drag for rectangle selection,")
    print("   or use ctrl + left click for polygon selection")
    print("4) Press 'C' to get a selected geometry and to save it")
    print("5) Press 'F' to switch to freeview mode")
    pcd = o3d.io.read_point_cloud(sys.argv[1])
    o3d.visualization.draw_geometries_with_editing([pcd])

Crop Selected Sphere

#!/usr/bin/env python3
import os
import numpy as np
import open3d as o3d


def pick_points(cloud):
    print("Press [shift + left click] to pick a point")
    print("Press [shift + right click] to undo point picking")
    print("Press 'Q' to close the window after picking points")
    vis = o3d.visualization.VisualizerWithEditing()
    vis.create_window()
    vis.add_geometry(cloud)
    vis.run()  # user picks points
    vis.destroy_window()
    return vis.get_picked_points() # a list of indices of picked points


if __name__ == "__main__":
    if 'SVGA_VGPU10' in os.environ:
        del os.environ['SVGA_VGPU10']
    cloud = o3d.io.read_point_cloud("../data/cloud.pcd")
    save_to_file = "../data/cropped.pcd"
    search_radius = 0.05
    
    # pick a point in interactive visualization
    point_indices = pick_points(cloud)
    picked_point = cloud.points[point_indices[0]] # take the first point
    print("picked point = " + str(picked_point))

    # find all neighbor points around the picked point
    cloud_tree = o3d.geometry.KDTreeFlann(cloud)
    [k, idx, _] = cloud_tree.search_radius_vector_3d(picked_point, search_radius)

    # crop the spherical region and save to a new file
    cropped = o3d.geometry.PointCloud()
    cropped.points = o3d.utility.Vector3dVector(np.asarray(cloud.points)[idx])
    cropped.colors = o3d.utility.Vector3dVector(np.asarray(cloud.colors)[idx])
    o3d.io.write_point_cloud(save_to_file, cropped)
    print("save the cropped point cloud to " + save_to_file)

    # color the spherical region to green to confirm
    np.asarray(cloud.colors)[idx[1:], :] = [0, 1, 0]
    o3d.visualization.draw_geometries([cloud])

    # show the cropped sphere
    sphere = o3d.io.read_point_cloud("../data/cropped.pcd")
    o3d.visualization.draw_geometries([sphere])

Keypoint Animation

#!/usr/bin/env python3
import os
import time
import open3d as o3d


def viewer(cloud, keypoints):
    flag  = False
    idx = -1
    max_idx = len(keypoints)
    vis = o3d.visualization.VisualizerWithKeyCallback()
    vis.create_window()
    vis.add_geometry(cloud)

    def next_one(vis):
        nonlocal idx
        if idx >= 0 and idx < max_idx - 1:
            idx = idx + 1
            vis.remove_geometry(keypoints[idx - 1], False)
            vis.add_geometry(keypoints[idx], False) # False: keep current viewpoint
            print("current keypoint = " + str(keypoints[idx].get_center()))
        elif idx == -1:
            idx = idx + 1
            vis.add_geometry(keypoints[idx], False)
            print("current keypoint = " + str(keypoints[idx].get_center()))
        elif idx == max_idx - 1:
            idx = idx + 1
            vis.remove_geometry(keypoints[idx - 1], False)
            print("current keypoint = no keypoint selected")

    def previous_one(vis):
        nonlocal idx
        if idx > 0 and idx < max_idx:
            idx = idx - 1
            vis.remove_geometry(keypoints[idx + 1], False)
            vis.add_geometry(keypoints[idx], False) # False: keep current viewpoint
            print("current keypoint = " + str(keypoints[idx].get_center()))
        elif idx == max_idx:
            idx = idx - 1
            vis.add_geometry(keypoints[idx], False)
            print("current keypoint = " + str(keypoints[idx].get_center()))
        elif idx == 0:
            idx = idx - 1
            vis.remove_geometry(keypoints[idx + 1], False)
            print("current keypoint = no keypoint selected")

    def forward_animation(vis):
        nonlocal flag
        if flag:
            next_one(vis)
            time.sleep(0.5)
 
    def pause_or_resume(vis):
        nonlocal flag
        if flag == False:
            flag = True
        else:
            flag = False

    # ord(X) turns X into unicode; need to use capital letter here
    vis.register_key_callback(ord("."), next_one)
    vis.register_key_callback(ord(","), previous_one)
    vis.register_key_callback(ord(" "), pause_or_resume)
    # animation callback will get run repeatability
    vis.register_animation_callback(forward_animation)
    vis.run()
    vis.destroy_window()


def keypoints_to_spheres(keypoints, r):
    spheres = []
    for keypoint in keypoints.points:
        sphere = o3d.geometry.TriangleMesh.create_sphere(radius=r)
        sphere.translate(keypoint)
        sphere.paint_uniform_color([1.0, 0.0, 0.0])
        spheres.append(sphere)
    return spheres


if __name__ == "__main__":
    if 'SVGA_VGPU10' in os.environ:
        del os.environ['SVGA_VGPU10']
    print("Demo for visualizing keypoints")
    print("Press '.' to view the next keypoint")
    print("Press ',' to view the previous keypoint")
    print("Press space key to start the animation")
    print("Press space key again to pause/resume")
    cloud = o3d.io.read_point_cloud("../data/cloud.pcd")
    keypoints = o3d.io.read_point_cloud("../data/keypoint.pcd")
    viewer(cloud, keypoints_to_spheres(keypoints, 0.04))

References

PreviousRegistrationNextTools

Last updated 3 years ago

Was this helpful?

Interactive visualization tutorial
Non-blocking visualization tutorial
Python code examples for visualization