LoCoBot Camera

class pyrobot.robots.locobot.camera.LoCoBotCamera(configs, ns='')[source]

Bases: pyrobot.sensors.camera.Camera

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

__init__(configs, ns='')[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.

property 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