Here lies API documentation for PyRobot. For tutorials on using PyRobot please refer to the PyRobot.
PyRobot is built around the following core classes that encapsulate different components of a robot.
pyrobot.core.
Robot
(robot_name, use_arm=True, use_base=True, use_camera=True, use_gripper=True, arm_config={}, base_config={}, camera_config={}, gripper_config={})[source]¶This is the main interface class that is composed of key robot modules (base, arm, gripper, and camera). This class builds robot specific objects by reading a configuration and instantiating the necessary robot module objects.
__init__
(robot_name, use_arm=True, use_base=True, use_camera=True, use_gripper=True, arm_config={}, base_config={}, camera_config={}, gripper_config={})[source]¶Constructor for the Robot class
Parameters: |
|
---|
pyrobot.core.
Base
(configs)[source]¶Bases: object
This is a parent class on which the robot specific Base classes would be built.
__init__
(configs)[source]¶The consturctor for Base class.
Parameters: | configs (YACS CfgNode) – configurations for base |
---|
get_state
(state_type)[source]¶Returns the requested base pose in the (x,y, yaw) format.
Parameters: | state_type (string) – Requested state type. Ex: Odom, SLAM, etc |
---|---|
Returns: | pose: pose of the form [x, y, yaw] |
Return type: | list |
go_to_absolute
(xyt_position, use_map, close_loop, smooth)[source]¶Moves the robot to the robot to given goal state in the world frame.
Parameters: |
|
---|
go_to_relative
(xyt_position, use_map, close_loop, smooth)[source]¶Moves the robot to the robot to given goal state relative to its initial pose.
Parameters: |
|
---|
set_vel
(fwd_speed, turn_speed, exe_time=1)[source]¶Set the moving velocity of the base
Parameters: |
|
---|
track_trajectory
(states, controls, close_loop)[source]¶State trajectory that the robot should track.
Parameters: |
|
---|
pyrobot.core.
Arm
(configs, moveit_planner='ESTkConfigDefault', analytical_ik=None, use_moveit=True)[source]¶Bases: object
This is a parent class on which the robot specific Arm classes would be built.
__init__
(configs, moveit_planner='ESTkConfigDefault', analytical_ik=None, use_moveit=True)[source]¶Constructor for Arm parent class.
Parameters: |
|
---|
compute_fk_position
(joint_positions, des_frame)[source]¶Given joint angles, compute the pose of desired_frame with respect to the base frame (self.configs.ARM.ARM_BASE_FRAME). The desired frame must be in self.arm_link_names
Parameters: |
|
---|---|
Returns: | translational vector and rotational matrix |
Return type: | np.ndarray, np.ndarray |
compute_fk_velocity
(joint_positions, joint_velocities, des_frame)[source]¶Given joint_positions and joint velocities, compute the velocities of des_frame with respect to the base frame
Parameters: |
|
---|---|
Returns: | translational and rotational velocities (vx, vy, vz, wx, wy, wz) |
Return type: | np.ndarray |
compute_ik
(position, orientation, qinit=None, numerical=True)[source]¶Inverse kinematics
Parameters: |
|
---|---|
Returns: | None or joint positions |
Return type: | np.ndarray |
get_ee_pose
(base_frame)[source]¶Return the end effector pose with respect to the base_frame
Parameters: | base_frame (string) – reference frame |
---|---|
Returns: | tuple (trans, rot_mat, quat) trans: translational vector (shape: \([3, 1]\)) rot_mat: rotational matrix (shape: \([3, 3]\)) quat: rotational matrix in the form of quaternion (shape: \([4,]\)) |
Return type: | tuple or ROS PoseStamped |
get_jacobian
(joint_angles)[source]¶Return the geometric jacobian on the given joint angles. Refer to P112 in “Robotics: Modeling, Planning, and Control”
Parameters: | joint_angles (list or flattened np.ndarray) – joint_angles |
---|---|
Returns: | jacobian |
Return type: | np.ndarray |
get_joint_angle
(joint)[source]¶Return the joint angle of the ‘joint’
Parameters: | joint (string) – joint name |
---|---|
Returns: | joint angle |
Return type: | float |
get_joint_torque
(joint)[source]¶Return the joint torque of the ‘joint’
Parameters: | joint (string) – joint name |
---|---|
Returns: | joint torque |
Return type: | float |
get_joint_velocities
()[source]¶Return the joint velocities
Returns: | joint_vels |
---|---|
Return type: | np.ndarray |
get_joint_velocity
(joint)[source]¶Return the joint velocity of the ‘joint’
Parameters: | joint (string) – joint name |
---|---|
Returns: | joint velocity |
Return type: | float |
get_transform
(src_frame, dest_frame)[source]¶Return the transform from the src_frame to dest_frame
Parameters: |
|
---|---|
Returns: | tuple (trans, rot_mat, quat ) trans: translational vector (shape: \([3, 1]\)) rot_mat: rotational matrix (shape: \([3, 3]\)) quat: rotational matrix in the form of quaternion (shape: \([4,]\)) |
Return type: | tuple or ROS PoseStamped |
move_ee_xyz
(displacement, eef_step=0.005, numerical=True, plan=True, **kwargs)[source]¶Keep the current orientation fixed, move the end effector in {xyz} directions
Parameters: |
|
---|---|
Returns: | whether the movement is successful or not |
Return type: | bool |
pose_ee
¶Return the end effector pose w.r.t ‘ARM_BASE_FRAME’
Returns: | trans: translational vector (shape: \([3, 1]\)) rot_mat: rotational matrix (shape: \([3, 3]\)) quat: rotational matrix in the form of quaternion (shape: \([4,]\)) |
---|---|
Return type: | tuple (trans, rot_mat, quat) |
set_ee_pose
(position, orientation, plan=True, wait=True, numerical=True, **kwargs)[source]¶Commands robot arm to desired end-effector pose (w.r.t. ‘ARM_BASE_FRAME’). Computes IK solution in joint space and calls set_joint_positions. Will wait for command to complete if wait is set to True.
Parameters: |
|
---|---|
Returns: | Returns True if command succeeded, False otherwise |
Return type: | bool |
set_joint_positions
(positions, plan=True, wait=True, **kwargs)[source]¶Sets the desired joint angles for all arm joints
Parameters: |
|
---|---|
Returns: | True if successful; False otherwise (timeout, etc.) |
Return type: | bool |
Here are the wrapper definitions for using PyRobot with the LoCoBot robot.
locobot.base.
LoCoBotBase
(configs, map_img_dir=None, base_controller='ilqr', base_planner=None, base=None)[source]¶Bases: pyrobot.core.Base
This is a common base class for the locobot and locobot-lite base.
__init__
(configs, map_img_dir=None, base_controller='ilqr', base_planner=None, base=None)[source]¶The constructor for LoCoBotBase class.
Parameters: |
|
---|
get_state
(state_type)[source]¶Returns the requested base pose in the (x,y, yaw) format as computed either from Wheel encoder readings or Visual-SLAM
Parameters: | state_type (string) – Requested state type. Ex: Odom, SLAM, etc |
---|---|
Returns: | pose of the form [x, y, yaw] |
Return type: | list |
go_to_absolute
(xyt_position, use_map=False, close_loop=True, smooth=False)[source]¶Moves the robot to the robot to given goal state in the world frame.
Parameters: |
|
---|
go_to_relative
(xyt_position, use_map=False, close_loop=True, smooth=False)[source]¶Moves the robot to the robot to given goal state relative to its initial pose.
Parameters: |
|
---|
track_trajectory
(states, controls=None, close_loop=True)[source]¶State trajectory that the robot should track.
Parameters: |
|
---|
Here are the controller classes for the Base.
locobot.base_controllers.
ProportionalControl
(bot_base, ctrl_pub, configs)[source]¶This class encapsulates and provides interface to a Proportional controller used to control the base
__init__
(bot_base, ctrl_pub, configs)[source]¶The constructor for ProportionalControl class.
Parameters: |
|
---|
go_to_absolute
(xyt_position, close_loop=True, smooth=False)[source]¶Moves the robot to the robot to given goal state in the world frame using proportional control.
Parameters: |
|
---|
locobot.base_controllers.
ILQRControl
(bot_base, ctrl_pub, configs)[source]¶Bases: locobot.base_control_utils.TrajectoryTracker
Class to implement LQR based feedback controllers on top of mobile bases.
__init__
(bot_base, ctrl_pub, configs)[source]¶Constructor for ILQR based Control.
Parameters: |
|
---|
go_to_absolute
(xyt_position, close_loop=True, smooth=True)[source]¶Moves the robot to the robot to given goal state in the world frame using ILQR control.
Parameters: |
|
---|
go_to_relative
(xyt_position, close_loop=True, smooth=True)[source]¶Relative pose that the robot should go to.
track_trajectory
(states, controls=None, close_loop=True)[source]¶State trajectory that the robot should track using ILQR control.
Parameters: |
|
---|
locobot.base_controllers.
MoveBaseControl
(base_state, configs)[source]¶Bases: object
This class encapsulates and provides interface to move_base controller used to control the base
__init__
(base_state, configs)[source]¶The constructor for MoveBaseControl class.
Parameters: |
|
---|
go_to_absolute
(xyt_position, close_loop=True, smooth=False)[source]¶Moves the robot to the robot to given goal state in the world frame.
Parameters: |
|
---|
locobot.base_control_utils.
TrajectoryTracker
(system)[source]¶Bases: object
Class to track a given trajectory. Uses LQR to generate a controller around the system that has been linearized around the trajectory.
execute_plan
(plan, close_loop=True)[source]¶Executes the plan, check for conditions like bumps, etc. Plan is object returned from generate_plan. Also stores the plan execution into variable self._trajectory_tracker_execution.
Parameters: |
|
---|---|
Returns: | Weather plan execution was successful or not. |
Return type: | bool |
generate_plan
(xs, us=None)[source]¶Generates a feedback controller that tracks the state trajectory specified by xs. Optionally specify a control trajectory us, otherwise it is automatically inferred.
Parameters: |
|
---|---|
Returns: | LQR controller that can track the specified trajectory. |
Return type: |
locobot.base_control_utils.
MoveBasePlanner
(configs)[source]¶This class enscapsulates the planning capabilities of the move_base and provides planning services and plan tracking services.
get_plan_absolute
(x, y, theta)[source]¶Gets plan as a list of poses in the world frame for the given (x, y, theta
move_to_goal
(goal, go_to_relative)[source]¶Moves the robot to the robot to given goal state in the absolute frame (world frame).
Parameters: |
|
---|
locobot.base_control_utils.
LQRSolver
(As=None, Bs=None, Cs=None, Qs=None, Rs=None, x_refs=None, u_refs=None)[source]¶Bases: object
This class implements a solver for a time-varying Linear Quadratic Regulator System. A time-varying LQR system is defined via affine time varying transition functions, and time-varying quadratic cost functions.Such a system can be solved using dynamic programming to obtain time-varying feedback control matrices that can be used to compute the control command given the state of the system at any given time step.
__init__
(As=None, Bs=None, Cs=None, Qs=None, Rs=None, x_refs=None, u_refs=None)[source]¶Constructor for LQR solver.
System definition: \(x_{t+1} = A_tx_t + B_tu_t + C_t\)
State cost: \(x^t_tQ_tx_t + x^t_tq + q\_\)
Control cost: \(u^t_tR_tu_t\)
Parameters: |
|
---|
get_control
(x, i)[source]¶Uses the stored solution to the system to output control cost if the system is in state x at time step i.
Parameters: |
|
---|---|
Returns: | feedback control that should be applied |
Return type: | numpy array (control_dim,) |
get_control_ls
(x, alpha, i)[source]¶Returns control but modulated via a step-size alpha.
Parameters: |
|
---|---|
Returns: | feedback control that should be applied |
Return type: | numpy array (control_dim,) |
locobot.base_control_utils.
ILQRSolver
(dyn_fn, Q_fn, R_fn, start_state, goal_state)[source]¶Bases: object
Iterative LQR solver for non-linear systems. Computes a linearization of the system at the current trajectory, and solves that linear system using LQR. This process is repeated.
__init__
(dyn_fn, Q_fn, R_fn, start_state, goal_state)[source]¶Constructor that sets up functions describing the system and costs.
Parameters: |
|
---|
get_step_size
(lqr_, ref_controls, ref_cost, ilqr_iter)[source]¶Search for the step size that improves the cost function over LQR iterations.
Parameters: |
|
---|---|
Returns: | step size, updated controls, updated cost |
Return type: | float, numpy array, float |
solve
(init_controls, ilqr_iters)[source]¶Solve the non-linear system.
Parameters: |
|
---|---|
Returns: | LQR Tracker, step_size, cost of solution |
Return type: | LQRSolver, int, cost |
unroll
(dyn_fn, start_state, controls)[source]¶Obtain state trajectory by applying controls on the system defined by the dynamics function dyn_fn.
Parameters: |
|
---|---|
Returns: | Sequence of states |
Return type: | numpy array |
locobot.arm.
LoCoBotArm
(configs, control_mode='position', moveit_planner='ESTkConfigDefault', use_moveit=True)[source]¶Bases: pyrobot.core.Arm
This class has functionality to control a robotic arm in joint and task space (with and without any motion planning), for position/velocity/torque control, etc.
__init__
(configs, control_mode='position', moveit_planner='ESTkConfigDefault', use_moveit=True)[source]¶The constructor for LoCoBotArm class.
Parameters: |
|
---|
go_home
(plan=False)[source]¶Commands robot to home position
Parameters: | plan (bool) – use moveit to plan the path or not |
---|
set_ee_pose_pitch_roll
(position, pitch, roll=None, plan=True, wait=True, numerical=True, **kwargs)[source]¶Commands robot arm to desired end-effector pose (w.r.t. ‘ARM_BASE_FRAME’). Computes IK solution in joint space and calls set_joint_positions. Will wait for command to complete if wait is set to True.
Parameters: |
|
---|---|
Return result: | Returns True if command succeeded, False otherwise |
Return type: | bool |
set_joint_torque
(joint_name, value)[source]¶Parameters: |
|
---|---|
Returns: | sucessful or not |
Return type: | bool |
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_link_transform
(src, tgt)[source]¶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: |
|
---|---|
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: |
|
---|---|
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) |
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: |
|
---|
set_pan_tilt
(pan, tilt, wait=True)[source]¶Sets both the pan and tilt joint angles to the specified values.
Parameters: |
|
---|
set_tilt
(tilt, wait=True)[source]¶Sets the tilt joint angle to the specified value.
Parameters: |
|
---|
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 |
locobot.gripper.
LoCoBotGripper
(configs, wait_time=3)[source]¶Bases: pyrobot.core.Gripper
Interface for gripper
__init__
(configs, wait_time=3)[source]¶The constructor for LoCoBotGripper class.
Parameters: |
|
---|
close
(wait=True)[source]¶Commands gripper to close fully
Parameters: | wait (bool) – True if blocking call and will return after target_joint is achieved, False otherwise |
---|
get_gripper_state
()[source]¶Return the gripper state.
Returns: | state state = -1: unknown gripper state state = 0: gripper is fully open state = 1: gripper is closing state = 2: there is an object in the gripper state = 3: gripper is fully closed |
---|---|
Return type: | int |
Here are the wrapper definitions for using PyRobot with the Sawyer robot.
sawyer.arm.
SawyerArm
(configs, moveit_planner='ESTkConfigDefault')[source]¶Bases: pyrobot.core.Arm
This class has functionality to control a Sawyer manipulator.
sawyer.gripper.
SawyerGripper
(configs, ee_name='right_gripper', calibrate=True, wait_time=3)[source]¶Bases: pyrobot.core.Gripper
Interface for gripper.
__init__
(configs, ee_name='right_gripper', calibrate=True, wait_time=3)[source]¶Parameters: |
|
---|
close
(position=None, wait=True)[source]¶Commands gripper to close fully
Parameters: |
|
---|