Camera

class locobot.camera.SimpleCamera(configs)[source]

Bases: pyrobot.core.Camera

This is camera class that interfaces with the Realsense camera on the locobot and locobot-lite. This class does not have the pan and tilt actuation capabilities for the camera.

__init__(configs)[source]

Constructor of the SimpleCamera class.

Parameters:configs (YACS CfgNode) – Camera specific configuration object
get_current_pcd(in_cam=True)[source]

Return the point cloud at current time step (one frame only)

Parameters:in_cam (bool) – return points in camera frame, otherwise, return points in base frame
Returns:tuple (pts, colors)

pts: point coordinates in world frame (shape: \([N, 3]\))

colors: rgb values for pts_in_cam (shape: \([N, 3]\))

Return type:tuple(np.ndarray, np.ndarray)
get_depth()[source]

This function returns the depth image perceived by the camera.

Return type:np.ndarray or None
get_intrinsics()[source]

This function returns the camera intrinsics.

Return type:np.ndarray

Returns the latest transformation from the target_frame to the source frame, i.e., the transform of source frame w.r.t target frame. If the returned transform is applied to data, it will transform data in the source_frame into the target_frame

For more information, please refer to http://wiki.ros.org/tf/Overview/Using%20Published%20Transforms

Parameters:
  • src (string) – source frame
  • tgt (string) – target frame
Returns:

tuple(trans, rot, T)

trans: translational vector (shape: \([3,]\))

rot: rotation matrix (shape: \([3, 3]\))

T: transofrmation matrix (shape: \([4, 4]\))

Return type:

tuple(np.ndarray, np.ndarray, np.ndarray)

get_rgb()[source]

This function returns the RGB image perceived by the camera.

Return type:np.ndarray or None
get_rgb_depth()[source]

This function returns both the RGB and depth images perceived by the camera.

Return type:np.ndarray or None
pix_to_3dpt(rs, cs, in_cam=False)[source]

Get the 3D points of the pixels in RGB images.

Parameters:
  • rs (list or np.ndarray) – rows of interest in the RGB image. It can be a list or 1D numpy array which contains the row indices. The default value is None, which means all rows.
  • cs (list or np.ndarray) – columns of interest in the RGB image. It can be a list or 1D numpy array which contains the column indices. The default value is None, which means all columns.
  • in_cam (bool) – return points in camera frame, otherwise, return points in base frame
Returns:

tuple (pts, colors)

pts: point coordinates in world frame (shape: \([N, 3]\))

colors: rgb values for pts_in_cam (shape: \([N, 3]\))

Return type:

tuple(np.ndarray, np.ndarray)

class locobot.camera.LoCoBotCamera(configs)[source]

Bases: locobot.camera.SimpleCamera

This is camera class that interfaces with the Realsense camera and the pan and tilt joints on the robot.

__init__(configs)[source]

Constructor of the LoCoBotCamera class.

Parameters:configs (YACS CfgNode) – Object containing configurations for camera, pan joint and tilt joint.
get_pan()[source]

Return the current pan joint angle of the robot camera.

Returns:pan: Pan joint angle
Return type:float
get_state()[source]

Return the current pan and tilt joint angles of the robot camera.

Returns:pan_tilt: A list the form [pan angle, tilt angle]
Return type:list
get_tilt()[source]

Return the current tilt joint angle of the robot camera.

Returns:tilt: Tilt joint angle
Return type:float
reset()[source]

This function resets the pan and tilt joints by actuating them to their home configuration.

set_pan(pan, wait=True)[source]

Sets the pan joint angle to the specified value.

Parameters:
  • pan (float) – value to be set for pan joint
  • wait (bool) – wait until the pan angle is set to the target angle.
set_pan_tilt(pan, tilt, wait=True)[source]

Sets both the pan and tilt joint angles to the specified values.

Parameters:
  • pan (float) – value to be set for pan joint
  • tilt (float) – value to be set for the tilt joint
  • wait (bool) – wait until the pan and tilt angles are set to the target angles.
set_tilt(tilt, wait=True)[source]

Sets the tilt joint angle to the specified value.

Parameters:
  • tilt (float) – value to be set for the tilt joint
  • wait (bool) – wait until the tilt angle is set to the target angle.
state

Return the current pan and tilt joint angles of the robot camera.

Returns:pan_tilt: A list the form [pan angle, tilt angle]
Return type:list