Detection

Classes for finding a set of bounding boxes around objects of interest in an image.

RgbdDetector

Abstract class for detection from an RGBD image.

class perception.RgbdDetector

Bases: object

Wraps methods for as many distinct objects in the image as possible.

detect(color_im, depth_im, cfg, camera_intr=None, T_camera_world=None)

Detects all relevant objects in an rgbd image pair.

Parameters:
  • color_im (ColorImage) – color image for detection
  • depth_im (DepthImage) – depth image for detection (corresponds to color image)
  • cfg (YamlConfig) – parameters of detection function
  • camera_intr (CameraIntrinsics) – intrinsics of the camera
  • T_camera_world (autolab_core.RigidTransform) – registration of the camera to world frame
Returns:

all detections in the image

Return type:

list of RgbdDetection

RgbdDetection

class perception.RgbdDetection(color_thumbnail, depth_thumbnail, bounding_box, binary_thumbnail=None, camera_intr=None, contour=None)

Bases: object

Struct to wrap the results of rgbd detection.

height

int – height of detected object in pixels

width

int – width of detected object in pixels

camera_intr

CameraIntrinsics – camera intrinsics that project the detected window into the camera center

query_im

ColorImage – binary segmask for detected object as a 3-channel color image, for backwards comp

color_im

ColorImage – color thumbnail of detected object, with object masked if binary mask available

depth_im

DepthImage – depth thumbnail of detected object, with object masked if binary mask available

binary_im

BinaryImage – binary segmask of detected object

depth_im_table

DepthImage – unmasked depth image, for backwards comp

cropped_ir_intrinsics

CameraIntrinsics – alias for camera_intr, for backwards comp

point_normal_cloud

PointNormalCloud – point cloud with normals for the detected object

image(render_mode)

Get the image associated with a particular render mode

RgbdForegroundMaskDetector

class perception.RgbdForegroundMaskDetector

Bases: perception.detector.RgbdDetector

Detect by identifying all connected components in the foreground of the images using background subtraction.

detect(color_im, depth_im, cfg, camera_intr=None, T_camera_world=None)

Detects all relevant objects in an rgbd image pair using foreground masking.

Parameters:
  • color_im (ColorImage) – color image for detection
  • depth_im (DepthImage) – depth image for detection (corresponds to color image)
  • cfg (YamlConfig) – parameters of detection function
  • camera_intr (CameraIntrinsics) – intrinsics of the camera
  • T_camera_world (autolab_core.RigidTransform) – registration of the camera to world frame
Returns:

all detections in the image

Return type:

list of RgbdDetection

RgbdForegroundMaskQueryImageDetector

class perception.RgbdForegroundMaskQueryImageDetector

Bases: perception.detector.RgbdDetector

Detect by identifying all connected components in the foreground of the images using background subtraction. Converts all detections within a specified area into query images for a cnn. Optionally resegements the images using KMeans to remove spurious background pixels.

detect(color_im, depth_im, cfg, camera_intr=None, T_camera_world=None, vis_foreground=False, vis_segmentation=False)

Detects all relevant objects in an rgbd image pair using foreground masking.

Parameters:
  • color_im (ColorImage) – color image for detection
  • depth_im (DepthImage) – depth image for detection (corresponds to color image)
  • cfg (YamlConfig) – parameters of detection function
  • camera_intr (CameraIntrinsics) – intrinsics of the camera
  • T_camera_world (autolab_core.RigidTransform) – registration of the camera to world frame
Returns:

all detections in the image

Return type:

list of RgbdDetection