airobot.sensor.camera.rgbdcam

class airobot.sensor.camera.rgbdcam.RGBDCamera(cfgs)[source]

Bases: airobot.sensor.camera.camera.Camera

A RGBD camera.

Parameters:

cfgs (YACS CfgNode) – configurations for the camera.

Variables:
  • cfgs (YACS CfgNode) – configurations for the end effector.
  • img_height (int) – height of the image.
  • img_width (int) – width of the image.
  • cam_ext_mat (np.ndarray) – extrinsic matrix (shape: \([4, 4]\)) for the camera (source frame: base frame. target frame: camera frame).
  • cam_int_mat (np.ndarray) – intrinsic matrix (shape: \([3, 3]\)) for the camera.
  • cam_int_mat_inv (np.ndarray) – inverse of the intrinsic matrix.
  • depth_scale (float) – ratio of the depth image value to true depth value.
  • depth_min (float) – minimum depth value considered in 3D reconstruction.
  • depth_max (float) – maximum depth value considered in 3D reconstruction.
get_cam_ext()[source]

Return the camera’s extrinsic matrix.

Returns:np.ndarray – extrinsic matrix (shape: \([4, 4]\)) for the camera (source frame: base frame. target frame: camera frame).
get_cam_int()[source]

Return the camera’s intrinsic matrix.

Returns:np.ndarray – intrinsic matrix (shape: \([3, 3]\)) for the camera.
get_pcd(in_world=True, filter_depth=True, depth_min=None, depth_max=None, cam_ext_mat=None, rgb_image=None, depth_image=None)[source]

Get the point cloud from the entire depth image in the camera frame or in the world frame.

Parameters:
  • in_world (bool) – return point cloud in the world frame, otherwise, return point cloud in the camera frame.
  • filter_depth (bool) – only return the point cloud with depth values lying in [depth_min, depth_max].
  • depth_min (float) – minimum depth value. If None, it will use the default minimum depth value defined in the config file.
  • depth_max (float) – maximum depth value. If None, it will use the default maximum depth value defined in the config file.
  • cam_ext_mat (np.ndarray) – camera extrinsic matrix (shape: \([4,4]\)). If provided, it will be used to compute the points in the world frame.
  • rgb_image (np.ndarray) – externally captured RGB image, if we want to convert a depth image captured outside this function to a point cloud. (shape \([H, W, 3]\))
  • depth_image (np.ndarray) – externally captured depth image, if we want to convert a depth image captured outside this function to a point cloud. (shape \([H, W]\))
Returns:

2-element tuple containing

  • np.ndarray: point coordinates (shape: \([N, 3]\)).
  • np.ndarray: rgb values (shape: \([N, 3]\)).

get_pix_3dpt(rs, cs, in_world=True, filter_depth=False, k=1, ktype='median', depth_min=None, depth_max=None, cam_ext_mat=None)[source]

Calculate the 3D position of pixels in the RGB image.

Parameters:
  • rs (int or list or np.ndarray) – rows of interest. It can be a list or 1D numpy array which contains the row indices. The default value is None, which means all rows.
  • cs (int or list or np.ndarray) – columns of interest. It can be a list or 1D numpy array which contains the column indices. The default value is None, which means all columns.
  • in_world (bool) – if True, return the 3D position in the world frame, Otherwise, return the 3D position in the camera frame.
  • filter_depth (bool) – if True, only pixels with depth values between [depth_min, depth_max] will remain.
  • k (int) – kernel size. A kernel (slicing window) will be used to get the neighboring depth values of the pixels specified by rs and cs. And depending on the ktype, a corresponding method will be applied to use some statistical value (such as minimum, maximum, median, mean) of all the depth values in the slicing window as a more robust estimate of the depth value of the specified pixels.
  • ktype (str) – what kind of statistical value of all the depth values in the sliced kernel to use as a proxy of the depth value at specified pixels. It can be median, min, max, mean.
  • depth_min (float) – minimum depth value. If None, it will use the default minimum depth value defined in the config file.
  • depth_max (float) – maximum depth value. If None, it will use the default maximum depth value defined in the config file.
  • cam_ext_mat (np.ndarray) – camera extrinsic matrix (shape: \([4,4]\)). If provided, it will be used to compute the points in the world frame.
Returns:

np.ndarray – 3D point coordinates of the pixels in camera frame (shape: \([N, 3]\)).

set_cam_ext(pos=None, ori=None, cam_ext=None)[source]

Set the camera extrinsic matrix.

Parameters:
  • pos (np.ndarray) – position of the camera (shape: \([3,]\)).
  • ori (np.ndarray) – orientation. It can be rotation matrix (shape: \([3, 3]\)) quaternion ([x, y, z, w], shape: \([4]\)), or euler angles ([roll, pitch, yaw], shape: \([3]\)).
  • cam_ext (np.ndarray) – extrinsic matrix (shape: \([4, 4]\)). If this is provided, pos and ori will be ignored.