sapien.sensor package
Submodules
sapien.sensor.activelight module
- class sapien.sensor.activelight.ActiveLightSensor(sensor_name: str, renderer: IPxrRenderer, scene: Scene, sensor_type: Optional[str] = 'd415', rgb_resolution: Optional[Tuple[int, int]] = None, ir_resolution: Optional[Tuple[int, int]] = None, rgb_intrinsic: Optional[ndarray] = None, ir_intrinsic: Optional[ndarray] = None, trans_pose_l: Optional[Pose] = None, trans_pose_r: Optional[Pose] = None, light_pattern: Optional[str] = None, max_depth: float = 10.0, min_depth: float = 0.2, ir_ambient_strength: float = 0.002, ir_light_dim_factor: float = 0.05)[source]
Bases:
SensorEntity
sapien.sensor.depth_processor module
- sapien.sensor.depth_processor.calc_depth_and_pointcloud(disparity: ndarray, mask: ndarray, q: ndarray, no_pointcloud: bool = False) Tuple[ndarray, object] [source]
Calculate depth and pointcloud.
- Parameters
disparity – Disparity
mask – Valid mask
q – Perspective transformation matrix
no_pointcloud –
- Return depth
Depth
- Return pointcloud
Pointcloud
- sapien.sensor.depth_processor.calc_disparity(imgl: ndarray, imgr: ndarray, method: str, *, ndisp: int = 128, min_disp: int = 0, use_census: bool = True, census_wsize: int = 7) ndarray [source]
Calculate disparity given a rectified image pair.
- Parameters
imgl – Left image
imgr – Right image
method – SGBM or BM
ndisp – max disparity
min_disp – min disparity
- Returns
disparity
- sapien.sensor.depth_processor.calc_main_depth_from_left_right_ir(ir_l: ndarray, ir_r: ndarray, l2r: ndarray, l2rgb: ndarray, k_l: ndarray, k_r: ndarray, k_main: ndarray, map1: ndarray, map2: ndarray, q: ndarray, method: str = 'SGBM', ndisp: int = 128, use_noise: bool = False, use_census: bool = True, register_depth: bool = True, register_blur_ksize: int = 5, main_cam_size=(1920, 1080), census_wsize=7, **kwargs) ndarray [source]
Calculate depth for rgb camera from left right ir images.
- Parameters
ir_l – left ir image
ir_r – right ir image
l2r – Change-of-coordinate matrix from left camera’s frame to right camera’s frame (in OpenCV coordinate system)
l2rgb – Change-of-coordinate matrix from left camera’s frame to RGB camera’s frame (in OpenCV coordinate system)
k_l – left intrinsic matrix
k_r – right intrinsic matrix
k_main – rgb intrinsic matrix
map1 – Left map for rectification
map2 – Right map for rectification
q – Perspective transformation matrix (for cv2.reprojectImageTo3D)
method – method for depth calculation (SGBM or BM)
use_noise – whether to simulate ir noise before processing
- Return depth
calculated depth
- sapien.sensor.depth_processor.calc_rectified_stereo_pair(imgl: ndarray, imgr: ndarray, map1: ndarray, map2: ndarray) Tuple[ndarray, ndarray] [source]
Rectify an image pair with given camera parameters.
- Parameters
imgl – Left image
imgr – Right image
map1 – Map for left camera
map2 – Map for right camera
- Return imgl_rect
Rectified left image
- Return imgr_rect
Rectified right image
- sapien.sensor.depth_processor.depth_post_processing(depth: ndarray, ksize: int = 5) ndarray [source]
- sapien.sensor.depth_processor.init_rectify_stereo(w: int, h: int, kl: ndarray, kr: ndarray, rt: ndarray, distortl: Optional[ndarray] = None, distortr: Optional[ndarray] = None) Tuple[ndarray, ndarray, ndarray] [source]
Initiate parameters needed for rectification with given camera parameters.
- Parameters
w – width of the image
h – height of the image
kl – Left intrinsic matrix
kr – Right intrinsic matrix
rt – Extrinsic matrix (left to right)
distortl – Left distortion coefficients
distortr – Right distortion coefficients
- Return map1
Map for left camera
- Return map2
Map for right camera
- Return q
Perspective transformation matrix (for cv2.reprojectImageTo3D)
- sapien.sensor.depth_processor.sim_ir_noise(img: ndarray, scale: float = 0.0, blur_ksize: int = 0, blur_ksigma: float = 0.03, speckle_shape: float = 398.12, speckle_scale: float = 0.00254, gaussian_mu: float = -0.231, gaussian_sigma: float = 0.83, seed: int = 0) ndarray [source]
Simulate IR camera noise.
Noise model from Landau et al. Simulating Kinect Infrared and Depth Images
- Parameters
img – Input IR image
scale – Scale for downsampling & applying gaussian blur
blur_ksize – Kernel size for gaussian blur
blur_ksigma – Kernel sigma for gaussian blur
speckle_shape – Shape parameter for speckle noise (Gamma distribution)
speckle_scale – Scale parameter for speckle noise (Gamma distribution)
gaussian_mu – mu for additive gaussian noise
gaussian_sigma – sigma for additive gaussian noise
seed – random seed used for numpy
- Returns
Processed IR image