Compute mesh for a given region defined by a binary mask

As in the title, I would like to either compute the mesh only for a given region of the frame defined by a binary mask (a numpy matrix) or to be able to cut the whole mesh as indicated by the binary mask. In all cases, I’m interested in computing the surface area (from the mesh) of the part identified by the mask. I would do so, for example, once every 30 frames, as indicated in the comments inside the following code, which is my starting point.

Thanks in advance for any suggestions.

import pyzed.sl as sl
import ogl_viewer.viewer as gl
import numpy as np


init_parameters = sl.InitParameters(
    depth_mode = sl.DEPTH_MODE.NEURAL,
    coordinate_units = sl.UNIT.METER,
    coordinate_system = sl.COORDINATE_SYSTEM.RIGHT_HANDED_Y_UP, # OpenGL's coordinate system is right_handed
    depth_maximum_distance = 8.
)

zed = sl.Camera()
status = zed.open(init_parameters)
if status != sl.ERROR_CODE.SUCCESS:
    print("Camera not opened : " + repr(status))
    exit()
else:
    print("Camera opened correctly: " + repr(status))

positional_tracking_parameters = sl.PositionalTrackingParameters()
positional_tracking_parameters.set_floor_as_origin = True # ?????
status = zed.enable_positional_tracking(positional_tracking_parameters)
if status != sl.ERROR_CODE.SUCCESS:
    print("Error in enable positional tracking : " + repr(status))
    exit()
else:
    print("Ok enable positional tracking : " + repr(status))

runtime_parameters = sl.RuntimeParameters(
    confidence_threshold = 50
)

image = sl.Mat()
point_cloud = sl.Mat()
pose = sl.Pose()

pymesh = sl.Mesh()
filter_params = sl.MeshFilterParameters() # not available for fused point cloud
filter_params.set(sl.MESH_FILTER.LOW) # sl.MESH_FILTER.MEDIUM

camera_infos = zed.get_camera_information()
viewer = gl.GLViewer()
viewer.init(
    camera_infos.camera_configuration.calibration_parameters.left_cam,
    pymesh,
    int(True))

frame_count = 0

camera_res = camera_infos.camera_configuration.resolution

display_resolution = sl.Resolution(min(camera_res.width, 1280), min(camera_res.height, 720))
rows = display_resolution.height
cols = display_resolution.width
radius = 170
center = (int((1/2) * rows), int((1/2) * cols))
# Generate grid of indices
y, x = np.ogrid[:rows, :cols]
# Create a binary circle in the mask
mask_np = ((x - center[1])**2 + (y - center[0])**2 <= radius**2).astype(np.uint8)

while viewer.is_available():
    # Grab an image, a RuntimeParameters object must be given to grab()
    if zed.grab(runtime_parameters) == sl.ERROR_CODE.SUCCESS:
        # Retrieve left image
        zed.retrieve_image(image, sl.VIEW.LEFT)
        # Update pose data (used for projection of the mesh over the current image)
        # Request an update of the spatial map every 30 frames (0.5s in HD720 mode)
        if frame_count >= 30 and viewer.chunks_updated():
            # Here I would like to get the mesh just for the region identified by 
            # ones in the mask_np binary numpy matrix
            # zed.extract_whole_spatial_map(pymesh)
            # pymesh.filter(filter_params, True)
            # pymesh.clear()
            try:
                print("number_of_triangles = ", pymesh.get_number_of_triangles())
                print("triangles = ", pymesh.triangles)
            except Exception as e:
                print("An error occured: ", str(e))
            viewer.clear_current_mesh()
            zed.request_spatial_map_async()
            frame_count = 0
        else:
            frame_count += 1
        
        tracking_state = zed.get_position(pose)#???
        spatial_mapping_state = zed.get_spatial_mapping_state()#????
        
        if zed.get_spatial_map_request_status_async() == sl.ERROR_CODE.SUCCESS:
            zed.retrieve_spatial_map_async(pymesh)
            viewer.update_chunks()

        change_state = viewer.update_view(
            image, 
            pose.pose_data(), 
            tracking_state, 
            spatial_mapping_state)
        
        print("change_state = ", change_state)
        print("tracking_state = ", tracking_state)
        print("spatial_mapping_state = ", spatial_mapping_state)

        if change_state:
            init_pose = sl.Transform()
            zed.reset_positional_tracking(init_pose)#????
            spatial_mapping_parameters = sl.SpatialMappingParameters(
                resolution = sl.MAPPING_RESOLUTION.HIGH,#sl.MAPPING_RESOLUTION.LOW
                mapping_range = sl.MAPPING_RANGE.MEDIUM,#sl.MAPPING_RANGE.FAR
                max_memory_usage = 2048,
                save_texture = False,
                use_chunk_only = True,
                reverse_vertex_order = False,
                map_type = sl.SPATIAL_MAP_TYPE.MESH)
            spatial_mapping_parameters.resolution_meter = sl.SpatialMappingParameters().get_resolution_preset(sl.MAPPING_RESOLUTION.MEDIUM)
            status = zed.enable_spatial_mapping(spatial_mapping_parameters)
            if status != sl.ERROR_CODE.SUCCESS:
                print("Error in enable spatial mapping: " + repr(status))
                exit()
            else:
                print("Ok enable spatial mapping: " + repr(status))
            pymesh.clear()
            viewer.clear_current_mesh()

image.free(memory_type=sl.MEM.CPU)
pymesh.clear()
# Disable modules and close camera
zed.disable_spatial_mapping()
zed.disable_positional_tracking()
zed.close()

# Free allocated memory before closing the camera
pymesh.clear()
image.free()
point_cloud.free()
# Close the ZED
zed.close()

Hi, this is not something you can do natively from the SDK. I think you should convert/export your mesh in another format, and then cut it with a third-party algorithm that reads your format.

Thank you for the very quick answer.
I’ve seen that with the method

pymesh.save(filepath)

one can save the mesh to an obj file. How can I save the mesh to a data structure compatible with another library like, say, open3d or pyvista?

I also saw that there should be the possibility of “manually” setting up a Region of Interest for the zed object representing the camera, but I could not get it to work.

Thanks a lot.

Actually, you are right. If you use the ROI feature, you can map only what’s in the ROI. Why couldn’t you make it work?

Thanks again for the reply.

I report below my code to set a region of interest (I could not find a sample in Python in the GitHub repo). This is still not the best option for me because I may have multiple regions of interest for a given grabbed frame (produced by a segmentation model).

import pyzed.sl as sl
import ogl_viewer.viewer as gl
import numpy as np


init_parameters = sl.InitParameters(
    depth_mode = sl.DEPTH_MODE.NEURAL,
    coordinate_units = sl.UNIT.METER,
    coordinate_system = sl.COORDINATE_SYSTEM.RIGHT_HANDED_Y_UP, # OpenGL's coordinate system is right_handed
    depth_maximum_distance = 8.
)

zed = sl.Camera()
status = zed.open(init_parameters)
if status != sl.ERROR_CODE.SUCCESS:
    print("Camera not opened : " + repr(status))
    exit()
else:
    print("Camera opened correctly: " + repr(status))

positional_tracking_parameters = sl.PositionalTrackingParameters()
positional_tracking_parameters.set_floor_as_origin = True # ?????
status = zed.enable_positional_tracking(positional_tracking_parameters)
if status != sl.ERROR_CODE.SUCCESS:
    print("Error in enable positional tracking : " + repr(status))
    exit()
else:
    print("Ok enable positional tracking : " + repr(status))

runtime_parameters = sl.RuntimeParameters(
    confidence_threshold = 50
)

image = sl.Mat()
point_cloud = sl.Mat()
pose = sl.Pose()

pymesh = sl.Mesh()
filter_params = sl.MeshFilterParameters() # not available for fused point cloud
filter_params.set(sl.MESH_FILTER.LOW) # sl.MESH_FILTER.MEDIUM

camera_infos = zed.get_camera_information()
viewer = gl.GLViewer()
viewer.init(
    camera_infos.camera_configuration.calibration_parameters.left_cam,
    pymesh,
    int(True))

frame_count = 0

camera_res = camera_infos.camera_configuration.resolution

display_resolution = sl.Resolution(min(camera_res.width, 1280), min(camera_res.height, 720))
rows = display_resolution.height
cols = display_resolution.width
radius = 170
center = (int((1/2) * rows), int((1/2) * cols))
# Generate grid of indices
y, x = np.ogrid[:rows, :cols]
# Create a binary circle in the mask
mask_np = ((x - center[1])**2 + (y - center[0])**2 <= radius**2).astype(np.uint8)

region_of_interest_sl = sl.Mat()
region_of_interest_np = region_of_interest_sl.get_data()
region_of_interest_np = mask_np
#I read in a thread that this is the workaround to create a sl.Mat object from a numpy matrix

zed.set_region_of_interest(region_of_interest_sl)

while viewer.is_available():
    # Grab an image, a RuntimeParameters object must be given to grab()
    if zed.grab(runtime_parameters) == sl.ERROR_CODE.SUCCESS:
        # Retrieve left image
        zed.retrieve_image(image, sl.VIEW.LEFT)
        # Update pose data (used for projection of the mesh over the current image)
        # Request an update of the spatial map every 30 frames (0.5s in HD720 mode)
        if frame_count >= 30 and viewer.chunks_updated():
            # Here I would like to get the mesh just for the region identified by 
            # ones in the mask_np binary numpy matrix
            # zed.extract_whole_spatial_map(pymesh)
            # pymesh.filter(filter_params, True)
            # pymesh.clear()
            try:
                print("number_of_triangles = ", pymesh.get_number_of_triangles())
                print("triangles = ", pymesh.triangles)
            except Exception as e:
                print("An error occured: ", str(e))
            viewer.clear_current_mesh()
            zed.request_spatial_map_async()
            frame_count = 0
        else:
            frame_count += 1
        
        tracking_state = zed.get_position(pose)#???
        spatial_mapping_state = zed.get_spatial_mapping_state()#????
        
        if zed.get_spatial_map_request_status_async() == sl.ERROR_CODE.SUCCESS:
            zed.retrieve_spatial_map_async(pymesh)
            viewer.update_chunks()

        change_state = viewer.update_view(
            image, 
            pose.pose_data(), 
            tracking_state, 
            spatial_mapping_state)
        
        print("change_state = ", change_state)
        print("tracking_state = ", tracking_state)
        print("spatial_mapping_state = ", spatial_mapping_state)

        if change_state:
            init_pose = sl.Transform()
            zed.reset_positional_tracking(init_pose)#????
            spatial_mapping_parameters = sl.SpatialMappingParameters(
                resolution = sl.MAPPING_RESOLUTION.HIGH,#sl.MAPPING_RESOLUTION.LOW
                mapping_range = sl.MAPPING_RANGE.MEDIUM,#sl.MAPPING_RANGE.FAR
                max_memory_usage = 2048,
                save_texture = False,
                use_chunk_only = True,
                reverse_vertex_order = False,
                map_type = sl.SPATIAL_MAP_TYPE.MESH)
            spatial_mapping_parameters.resolution_meter = sl.SpatialMappingParameters().get_resolution_preset(sl.MAPPING_RESOLUTION.MEDIUM)
            status = zed.enable_spatial_mapping(spatial_mapping_parameters)
            if status != sl.ERROR_CODE.SUCCESS:
                print("Error in enable spatial mapping: " + repr(status))
                exit()
            else:
                print("Ok enable spatial mapping: " + repr(status))
            pymesh.clear()
            viewer.clear_current_mesh()

image.free(memory_type=sl.MEM.CPU)
pymesh.clear()
# Disable modules and close camera
zed.disable_spatial_mapping()
zed.disable_positional_tracking()
zed.close()

# Free allocated memory before closing the camera
pymesh.clear()
image.free()
point_cloud.free()
# Close the ZED
zed.close()

Did you confirm with a cv.imshow that your ROI mat does contain the right data ?

About having multiple zone, this is totally possible. The ROI matrix actually is a mask.

If you are trying to ignore static object, you can also use the recently released automatic ROI feature. It guesses during an initialization step what part of it should be ignored. It will ignore anything that did not move during the initialization.

I confirm that mask_np is a numpy matrix of shape (720, 1280).

The commands

plt.imshow(mask1, cmap='gray', vmax=1, vmin=0)
plt.show()

illustrate a black-and-white image with a circle in the middle. The ones are inside the circle, and the zeros are outside.

What would be the expected behavior of the following API calls?

      measure_depth = sl.Mat()
      normal_map = sl.Mat()
      point_cloud = sl.Mat(resolution.width, resolution.height, sl.MAT_TYPE.F32_C4, sl.MEM.CPU)
      # ..... 
      if zed.grab(runtime_parameters) == sl.ERROR_CODE.SUCCESS:
          zed.retrieve_measure(measure_depth, sl.MEASURE.DEPTH)
          zed.retrieve_measure(point_cloud, sl.MEASURE.XYZRGBA, sl.MEM.CPU, resolution)
          zed.retrieve_measure(normal_map, sl.MEASURE.NORMALS)
          measure_depth_np = measure_depth.get_data()
          point_cloud_np = point_cloud.get_data()
          normal_map_np = normal_map.get_data()

I admit I’m asking this question now before I tested the code with the camera because, unfortunately, I don’t have it available now.
Should I see the mesh in the opengl window only over the mask-defined region?

Alberto

Yes, This is what will happen. Everything outside of the ROI mask will be ignored by ZED SDK’s modules - Depth, Spatial Mapping, Tracking, etc.