airobot.sensor.camera.rgbdcam_pybullet¶
-
class
airobot.sensor.camera.rgbdcam_pybullet.
RGBDCameraPybullet
(cfgs, pb_client)[source]¶ Bases:
airobot.sensor.camera.rgbdcam.RGBDCamera
RGBD Camera in Pybullet.
Parameters: cfgs (YACS CfgNode) – configurations for the camera.
Variables: - view_matrix (np.ndarray) – view matrix of opengl camera (shape: \([4, 4]\)).
- proj_matrix (np.ndarray) – projection matrix of opengl camera (shape: \([4, 4]\)).
-
get_images
(get_rgb=True, get_depth=True, get_seg=False, **kwargs)[source]¶ Return rgb, depth, and segmentation images.
Parameters: Returns: 2-element tuple (if get_seg is False) containing
- np.ndarray: rgb image (shape: [H, W, 3]).
- np.ndarray: depth image (shape: [H, W]).
3-element tuple (if get_seg is True) containing
- np.ndarray: rgb image (shape: [H, W, 3]).
- np.ndarray: depth image (shape: [H, W]).
- np.ndarray: segmentation mask image (shape: [H, W]), with pixel values corresponding to object id and link id. From the PyBullet documentation, the pixel value “combines the object unique id and link index as follows: value = objectUniqueId + (linkIndex+1)<<24 … for a free floating body without joints/links, the segmentation mask is equal to its body unique id, since its link index is -1.”.
-
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.
-
setup_camera
(focus_pt=None, dist=3, yaw=0, pitch=0, roll=0, height=None, width=None)[source]¶ Setup the camera view matrix and projection matrix. Must be called first before images are renderred.
Parameters: - focus_pt (list) – position of the target (focus) point, in Cartesian world coordinates.
- dist (float) – distance from eye (camera) to the focus point.
- yaw (float) – yaw angle in degrees, left/right around up-axis (z-axis).
- pitch (float) – pitch in degrees, up/down.
- roll (float) – roll in degrees around forward vector.
- height (float) – height of image. If None, it will use the default height from the config file.
- width (float) – width of image. If None, it will use the default width from the config file.