I’m working with the ZED SDK using the Python API to generate a fused point cloud and export it as a .ply
file. However, I’ve noticed that the resulting point cloud is significantly less dense and lower quality compared to the one generated by the built-in ZEDfu tool, even using same svo2 file on similar parameters.
I’m using request_spatial_map_async()
and retrieve_spatial_map_async()
for mapping and point cloud extraction in the loop, as per the documentation.
Generated by ZED SDK Python’s API
Generated by ZEDfu
Please take a look at given code below and suggest.
My Python code snippet used for generating the point cloud (attached below).
#
# Copyright (c) 2022, STEREOLABS.
#
# All rights reserved.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
# A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
# OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
# SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
# LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
# DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
# THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
# (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
# OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
#
########################################################################
"""
This sample shows how to capture a real-time 3D reconstruction
of the scene using the Spatial Mapping API. The resulting mesh
is displayed as a wireframe on top of the left image using OpenGL.
Spatial Mapping can be started and stopped with the Space Bar key
"""
import sys
import time
import pyzed.sl as sl
import ogl_viewer.viewer as gl
import argparse
def main():
init = sl.InitParameters()
init.sdk_verbose=1
init.depth_mode = sl.DEPTH_MODE.NEURAL
init.coordinate_units = sl.UNIT.METER
init.camera_resolution = sl.RESOLUTION.HD2K
# init.depth_stabilization= 40
init.coordinate_system = sl.COORDINATE_SYSTEM.RIGHT_HANDED_Z_UP_X_FWD # OpenGL's coordinate system is right_handed
init.depth_maximum_distance = 8
init.svo_real_time_mode = False
parse_args(init)
zed = sl.Camera()
status = zed.open(init)
if status != sl.ERROR_CODE.SUCCESS:
print("Camera Open : "+repr(status)+". Exit program.")
exit()
camera_infos = zed.get_camera_information()
pose = sl.Pose()
# tracking_state = sl.POSITIONAL_TRACKING_STATE.OFF
positional_tracking_parameters = sl.PositionalTrackingParameters()
positional_tracking_parameters.mode=sl.POSITIONAL_TRACKING_MODE.GEN_2
positional_tracking_parameters.set_floor_as_origin = False
positional_tracking_parameters.enable_area_memory = True
positional_tracking_parameters.enable_pose_smoothing =True
returned_state = zed.enable_positional_tracking(positional_tracking_parameters)
if returned_state != sl.ERROR_CODE.SUCCESS:
print(f"Positional Tracking Error: {status}")
zed.close()
exit(1)
if opt.build_mesh:
spatial_mapping_parameters = sl.SpatialMappingParameters(resolution = sl.MAPPING_RESOLUTION.MEDIUM,mapping_range = sl.MAPPING_RANGE.MEDIUM,max_memory_usage = 2048,save_texture = False,use_chunk_only = True,reverse_vertex_order = False,map_type = sl.SPATIAL_MAP_TYPE.MESH)
pymesh = sl.Mesh()
else :
spatial_mapping_parameters = sl.SpatialMappingParameters(resolution = sl.MAPPING_RESOLUTION.MEDIUM,mapping_range = sl.MAPPING_RANGE.MEDIUM,max_memory_usage = 4096,save_texture = False,use_chunk_only = False,reverse_vertex_order = False,map_type = sl.SPATIAL_MAP_TYPE.FUSED_POINT_CLOUD)
spatial_mapping_parameters.stability_counter = 4
spatial_mapping_parameters.resolution_meter = 0.05
pymesh = sl.FusedPointCloud()
# tracking_state = sl.POSITIONAL_TRACKING_STATE.OFF
# mapping_state = sl.SPATIAL_MAPPING_STATE.NOT_ENABLED
status = zed.enable_spatial_mapping(spatial_mapping_parameters)
if status != sl.ERROR_CODE.SUCCESS:
print(f"Spatial Mapping Error: {status}")
zed.close()
exit(1)
runtime_parameters = sl.RuntimeParameters()
runtime_parameters.confidence_threshold = 30
# runtime_parameters.texture_confidence_threshold = 100
mapping_activated = True
image = sl.Mat()
point_cloud = sl.Mat()
pose = sl.Pose()
# viewer = gl.GLViewer()
# viewer.init(zed.get_camera_information().camera_configuration.calibration_parameters.left_cam, pymesh, int(opt.build_mesh))
max_frames= zed.get_svo_number_of_frames()
frame_count=0
last_call = time.time()
while frame_count < max_frames:
# Grab an image, a RuntimeParameters object must be given to grab()
err = zed.grab(runtime_parameters)
if err == sl.ERROR_CODE.SUCCESS:
# zed.retrieve_image(image, sl.VIEW.LEFT)
# Update pose data (used for projection of the mesh over the current image)
tracking_state = zed.get_position(pose)
if time.time() - last_call > 0.5:
if zed.get_spatial_map_request_status_async() != sl.ERROR_CODE.SUCCESS:
zed.request_spatial_map_async()
last_call = time.time()
# zed.retrieve_spatial_map_async(pymesh)
if zed.get_spatial_map_request_status_async() == sl.ERROR_CODE.SUCCESS:
zed.retrieve_spatial_map_async(pymesh)
print("Updated fused point cloud")
# zed.request_spatial_map_async()
# last_call = time.time()
# if zed.get_spatial_map_request_status_async() == sl.ERROR_CODE.SUCCESS:
# zed.retrieve_spatial_map_async(pymesh)
print("Processing frame no "+ str(frame_count))
frame_count += 1
elif err == sl.ERROR_CODE.END_OF_SVOFILE_REACHED:
break
print("Extracting and saving point cloud...")
status = zed.extract_whole_spatial_map(pymesh)
if status == sl.ERROR_CODE.SUCCESS:
filepath = "/home/ceinfo/Documents/spatial_output/sample.ply"
status = pymesh.save(filepath, typeMesh=sl.MESH_FILE_FORMAT.PLY)
if status:
print(f"Point cloud saved successfully: {filepath}")
else:
print("Failed to save point cloud")
zed.disable_spatial_mapping()
zed.disable_positional_tracking()
zed.close()
pymesh.clear()
image.free()
image.free(memory_type=sl.MEM.CPU)
pymesh.clear()
# Disable modules and close camera
# Free allocated memory before clsing the camera
pymesh.clear()
image.free()
point_cloud.free()
# Close the ZED
zed.close()
def parse_args(init):
if len(opt.input_svo_file)>0 and opt.input_svo_file.endswith(".svo2"):
init.set_from_svo_file(opt.input_svo_file)
print("[Sample] Using SVO File input: {0}".format(opt.input_svo_file))
elif len(opt.ip_address)>0 :
ip_str = opt.ip_address
if ip_str.replace(':','').replace('.','').isdigit() and len(ip_str.split('.'))==4 and len(ip_str.split(':'))==2:
init.set_from_stream(ip_str.split(':')[0],int(ip_str.split(':')[1]))
print("[Sample] Using Stream input, IP : ",ip_str)
elif ip_str.replace(':','').replace('.','').isdigit() and len(ip_str.split('.'))==4:
init.set_from_stream(ip_str)
print("[Sample] Using Stream input, IP : ",ip_str)
else :
print("Unvalid IP format. Using live stream")
if __name__ == "__main__":
parser = argparse.ArgumentParser()
parser.add_argument('--input_svo_file', type=str, help='Path to an .svo file, if you want to replay it',default = '')
parser.add_argument('--ip_address', type=str, help='IP Adress, in format a.b.c.d:port or a.b.c.d, if you have a streaming setup', default = '')
parser.add_argument('--resolution', type=str, help='Resolution, can be either HD2K, HD1200, HD1080, HD720, SVGA or VGA', default = '')
parser.add_argument('--build_mesh', help = 'Either the script should plot a mesh or point clouds of surroundings', action='store_true')
opt = parser.parse_args()
if len(opt.input_svo_file)>0 and len(opt.ip_address)>0:
print("Specify only input_svo_file or ip_address, or none to use wired camera, not both. Exit program")
exit()
main()
Thanks in Advance