polymetis package

Subpackages

Submodules

polymetis.robot_interface module

class polymetis.robot_interface.BaseRobotInterface(ip_address: str = 'localhost', port: int = 50051, enforce_version=True, use_mirror_sim: bool = False, mirror_cfg: Optional[DictConfig] = None, mirror_ip: str = '', mirror_port: int = -1, mirror_metadata: Optional[DictConfig] = None)

Bases: object

Base robot interface class to initialize a connection to a gRPC controller manager server.

Parameters:
  • ip_address – IP address of the gRPC-based controller manager server.

  • port – Port to connect to on the IP address.

clean_mirror_after_forward()
get_previous_interval(timeout: Optional[float] = None) LogInterval

Get the log indices associated with the currently running policy.

get_previous_log(timeout: Optional[float] = None) List[RobotState]

Get the list of RobotStates associated with the currently running policy.

Parameters:

timeout – Amount of time (in seconds) to wait before throwing a TimeoutError.

Returns:

If successful, returns a list of RobotState objects.

get_robot_state() RobotState

Returns the latest RobotState.

is_running_policy() bool
send_torch_policy(torch_policy: PolicyModule, blocking: bool = True, timeout: Optional[float] = None, use_mirror: bool = False) List[RobotState]

Sends the ScriptableTorchPolicy to the server.

Parameters:
  • torch_policy – An instance of ScriptableTorchPolicy to control the robot.

  • blocking – If True, blocks until the policy is finished executing, then returns the list of RobotStates.

  • timeout – Amount of time (in seconds) to wait before throwing a TimeoutError.

Returns:

If blocking, returns a list of RobotState objects. Otherwise, returns None.

setup_mirror_for_forward()
sync_with_mirror()
terminate_current_policy(return_log: bool = True, timeout: Optional[float] = None) List[RobotState]

Terminates the currently running policy and (optionally) return its trajectory.

Parameters:
  • return_log – whether or not to block & return the policy’s trajectory.

  • timeout – Amount of time (in seconds) to wait before throwing a TimeoutError.

Returns:

If return_log, returns the list of RobotStates the list of RobotStates corresponding to the current policy’s execution.

unsync_with_mirror()
update_current_policy(param_dict: Dict[str, Tensor]) int

Updates the current policy’s with a (possibly incomplete) dictionary holding the updated values.

Parameters:

param_dict – A dictionary mapping from param_name to updated torch.Tensor values.

Returns:

Index offset from the beginning of the episode when the update was applied.

class polymetis.robot_interface.ParamDictContainer(param_dict: Dict[str, Tensor])

Bases: Module

A torch.nn.Module container for a parameter key.

Note

This is necessary because TorchScript can only script modules, not tensors or dictionaries.

Parameters:

param_dict – The dictionary mapping parameter names to values.

forward() Dict[str, Tensor]

Simply returns the wrapped parameter dictionary.

param_dict: Dict[str, Tensor]
class polymetis.robot_interface.RobotInterface(time_to_go_default: float = 1.0, use_grav_comp: bool = True, *args, **kwargs)

Bases: BaseRobotInterface

Adds user-friendly helper methods to automatically construct some policies with sane defaults.

Parameters:
  • time_to_go_default – Default amount of time for policies to run, if not given.

  • use_grav_comp – If True, assumes that gravity compensation torques are added to the given torques.

get_ee_pose() Tuple[Tensor, Tensor]

Computes forward kinematics on the current joint angles.

Returns:

3D end-effector position torch.Tensor: 4D end-effector orientation as quaternion

Return type:

torch.Tensor

get_jacobian()
get_joint_angles() Tensor

Functionally identical to get_joint_positions. This method is being deprecated in favor of `get_joint_positions`.

get_joint_positions() Tensor
get_joint_velocities() Tensor
go_home(use_mirror=False, *args, **kwargs) List[RobotState]

Calls move_to_joint_positions to the current home positions.

move_ee_xyz(displacement: Tensor, use_orient: bool = True, **kwargs) List[RobotState]

Functionally identical to calling move_to_ee_pose with the argument delta=True. This method is being deprecated in favor of `move_to_ee_pose`.

move_joint_positions(delta_positions, *args, **kwargs) List[RobotState]

Functionally identical to calling move_to_joint_positions with the argument delta=True. This method is being deprecated in favor of `move_to_joint_positions`.

move_to_ee_pose(position: Tensor, orientation: Optional[Tensor] = None, time_to_go: Optional[float] = None, delta: bool = False, Kx: Optional[Tensor] = None, Kxd: Optional[Tensor] = None, op_space_interp: bool = True, **kwargs) List[RobotState]

Uses an operational space controller to move to a desired end-effector position (and, optionally orientation). :param positions: Desired target end-effector position. :param positions: Desired target end-effector orientation (quaternion). :param time_to_go: Amount of time to execute the motion. Uses an adaptive value if not specified (see _adaptive_time_to_go for details). :param delta: Whether the specified position and orientation are relative to current pose or absolute. :param Kx: P gains for the tracking controller. Uses default values if not specified. :param Kxd: D gains for the tracking controller. Uses default values if not specified. :param op_space_interp: Interpolate trajectory in operational space, resulting in a straight line in 3D space instead of the shortest path in joint movement space.

Returns:

Same as send_torch_policy

move_to_joint_positions(positions: Tensor, time_to_go: Optional[float] = None, delta: bool = False, Kq: Optional[Tensor] = None, Kqd: Optional[Tensor] = None, **kwargs) List[RobotState]

Uses JointGoToPolicy to move to the desired positions with the given gains. :param positions: Desired target joint positions. :param time_to_go: Amount of time to execute the motion. Uses an adaptive value if not specified (see _adaptive_time_to_go for details). :param delta: Whether the specified positions are relative to current pose or absolute. :param Kq: Joint P gains for the tracking controller. Uses default values if not specified. :param Kqd: Joint D gains for the tracking controller. Uses default values if not specified.

Returns:

Same as send_torch_policy

pose_ee() Tuple[Tensor, Tensor]

Functionally identical to get_ee_pose. This method is being deprecated in favor of `get_ee_pose`.

set_ee_pose(*args, **kwargs) List[RobotState]

Functionally identical to move_to_ee_pose. This method is being deprecated in favor of `move_to_ee_pose`.

set_home_pose(home_pose: Tensor)

Sets the home pose for go_home() to use.

set_joint_positions(desired_positions, *args, **kwargs) List[RobotState]

Functionally identical to move_to_joint_positions. This method is being deprecated in favor of `move_to_joint_positions`.

set_robot_model(robot_description_path: str, ee_link_name: Optional[str] = None)

Loads the URDF as a RobotModelPinocchio.

solve_inverse_kinematics(position: Tensor, orientation: Tensor, q0: Tensor, tol: float = 0.001) Tuple[Tensor, bool]

Compute inverse kinematics given desired EE pose

start_cartesian_impedance(Kx=None, Kxd=None, **kwargs)

Starts Cartesian position control mode. Runs an non-blocking Cartesian impedance controller. The desired EE pose can be updated using update_desired_ee_pose

start_joint_impedance(Kq=None, Kqd=None, adaptive=True, **kwargs)

Starts joint position control mode. Runs an non-blocking joint impedance controller. The desired joint positions can be updated using update_desired_joint_positions

start_joint_velocity_control(joint_vel_desired, hz=None, Kq=None, Kqd=None, **kwargs)

Starts joint velocity control mode. Runs a non-blocking joint velocity controller. The desired joint velocities can be updated using update_desired_joint_velocities

update_desired_ee_pose(position: Optional[Tensor] = None, orientation: Optional[Tensor] = None) int

Update the desired EE pose used by the Cartesian position control mode. Requires starting a Cartesian impedance controller with start_cartesian_impedance beforehand.

update_desired_joint_positions(positions: Tensor) int

Update the desired joint positions used by the joint position control mode. Requires starting a joint impedance controller with start_joint_impedance beforehand.

update_desired_joint_velocities(velocities: Tensor)

Update the desired joint velocities used by the joint velocities control mode. Requires starting a joint velocities controller with start_joint_velocity_control beforehand.

Module contents