panda_py package

Introduction

panda-py is a Python library for the Franka Emika Robot System that allows you to program and control the robot in real-time.

class panda_py.Panda(self: panda_py._core.Panda, hostname: str, name: str = 'panda', realtime_config: panda_py.libfranka.RealtimeConfig = <RealtimeConfig.kIgnore: 1>)

Bases: pybind11_object

The main interface of panda-py to control the robot.

create_context(self: panda_py._core.Panda, frequency: float, max_runtime: float = 0.0, max_iter: int = 0) panda_py._core.PandaContext
disable_logging(self: panda_py._core.Panda) None
enable_logging(self: panda_py._core.Panda, buffer_size: int) None
get_log(self: panda_py._core.Panda) dict[str, list[numpy.ndarray[numpy.float64[m, 1]]]]
get_model(self: panda_py._core.Panda) panda_py.libfranka.Model
get_orientation(self: panda_py._core.Panda, scalar_first: bool = False) numpy.ndarray[numpy.float64[4, 1]]

Get current end-effector orientation \(\mathbf q = (\vec{v},\ r),~~ \mathbf q \in \mathbb{H},~~ \vec{v}\in \mathbb{R}^3,~~ r \in \mathbb{R}\) in robot base frame.

Parameters:

scalar_first – If True returns quaternion in scalar first representation (default: False)

Returns:

Vector of shape (4,) holding quaternion coefficients.

get_pose(self: panda_py._core.Panda) numpy.ndarray[numpy.float64[4, 4]]
get_position(self: panda_py._core.Panda) numpy.ndarray[numpy.float64[3, 1]]

Current end-effector position in robot base frame.

get_robot(self: panda_py._core.Panda) panda_py.libfranka.Robot

Get a reference to the libfranka.Robot class behind this instance.

get_state(self: panda_py._core.Panda) panda_py.libfranka.RobotState

Get a copy of the last libfranka.RobotState received from the robot.

move_to_joint_position(*args, **kwargs)

Overloaded function.

  1. move_to_joint_position(self: panda_py._core.Panda, waypoints: list[numpy.ndarray[numpy.float64[7, 1]]], speed_factor: float = 0.2, stiffness: numpy.ndarray[numpy.float64[7, 1]] = array([600., 600., 600., 600., 250., 150., 50.]), damping: numpy.ndarray[numpy.float64[7, 1]] = array([50., 50., 50., 20., 20., 20., 10.]), dq_threshold: float = 0.001, success_threshold: float = 0.01) -> bool

  2. move_to_joint_position(self: panda_py._core.Panda, positions: numpy.ndarray[numpy.float64[7, 1]], speed_factor: float = 0.2, stiffness: numpy.ndarray[numpy.float64[7, 1]] = array([600., 600., 600., 600., 250., 150., 50.]), damping: numpy.ndarray[numpy.float64[7, 1]] = array([50., 50., 50., 20., 20., 20., 10.]), dq_threshold: float = 0.001, success_threshold: float = 0.01) -> bool

move_to_pose(*args, **kwargs)

Overloaded function.

  1. move_to_pose(self: panda_py._core.Panda, positions: list[numpy.ndarray[numpy.float64[3, 1]]], orientations: list[numpy.ndarray[numpy.float64[4, 1]]], speed_factor: float = 0.2, impedance: numpy.ndarray[numpy.float64[6, 6]] = array([[800., 0., 0., 0., 0., 0.], [ 0., 800., 0., 0., 0., 0.], [ 0., 0., 800., 0., 0., 0.], [ 0., 0., 0., 40., 0., 0.], [ 0., 0., 0., 0., 40., 0.], [ 0., 0., 0., 0., 0., 40.]]), damping_ratio: float = 1.0, nullspace_stiffness: float = 15.0, dq_threshold: float = 0.001, success_threshold: float = 0.01) -> bool

    Moves the end-effector from the current pose through the provided waypoints in piece-wise linear segments. The waypoints are given as lists of positions \(\in \mathbb{R}^3\) and orientations \(\mathbf q = (\vec{v},\ r),~~ \mathbf q \in \mathbb{H},~~ \vec{v}\in \mathbb{R}^3,~~ r \in \mathbb{R}\), i.e. quaternions with scalar last. The computed trajectory is time-optimal.

  2. move_to_pose(self: panda_py._core.Panda, position: numpy.ndarray[numpy.float64[3, 1]], orientation: numpy.ndarray[numpy.float64[4, 1]], speed_factor: float = 0.2, impedance: numpy.ndarray[numpy.float64[6, 6]] = array([[800., 0., 0., 0., 0., 0.], [ 0., 800., 0., 0., 0., 0.], [ 0., 0., 800., 0., 0., 0.], [ 0., 0., 0., 40., 0., 0.], [ 0., 0., 0., 0., 40., 0.], [ 0., 0., 0., 0., 0., 40.]]), damping_ratio: float = 1.0, nullspace_stiffness: float = 15.0, dq_threshold: float = 0.001, success_threshold: float = 0.01) -> bool

    Same as move_to_pose() above, but only one target pose given as position and orientation directly.

  3. move_to_pose(self: panda_py._core.Panda, pose: list[numpy.ndarray[numpy.float64[4, 4]]], speed_factor: float = 0.2, impedance: numpy.ndarray[numpy.float64[6, 6]] = array([[800., 0., 0., 0., 0., 0.], [ 0., 800., 0., 0., 0., 0.], [ 0., 0., 800., 0., 0., 0.], [ 0., 0., 0., 40., 0., 0.], [ 0., 0., 0., 0., 40., 0.], [ 0., 0., 0., 0., 0., 40.]]), damping_ratio: float = 1.0, nullspace_stiffness: float = 15.0, dq_threshold: float = 0.001, success_threshold: float = 0.01) -> bool

    Same as move_to_pose() above, but waypoints are given as a list of homogeneous transforms \(\in \mathbb{R}^{4\times 4}\).

  4. move_to_pose(self: panda_py._core.Panda, pose: numpy.ndarray[numpy.float64[4, 4]], speed_factor: float = 0.2, impedance: numpy.ndarray[numpy.float64[6, 6]] = array([[800., 0., 0., 0., 0., 0.], [ 0., 800., 0., 0., 0., 0.], [ 0., 0., 800., 0., 0., 0.], [ 0., 0., 0., 40., 0., 0.], [ 0., 0., 0., 0., 40., 0.], [ 0., 0., 0., 0., 0., 40.]]), damping_ratio: float = 1.0, nullspace_stiffness: float = 15.0, dq_threshold: float = 0.001, success_threshold: float = 0.01) -> bool

    Same as move_to_pose() above, but only one target pose given as homogeneous transform \(\in \mathbb{R}^{4\times 4}\).

move_to_start(self: panda_py._core.Panda, speed_factor: float = 0.2, stiffness: numpy.ndarray[numpy.float64[7, 1]] = array([600., 600., 600., 600., 250., 150., 50.]), damping: numpy.ndarray[numpy.float64[7, 1]] = array([50., 50., 50., 20., 20., 20., 10.]), dq_threshold: float = 0.001, success_threshold: float = 0.01) bool

Convenience function similar to move_to_pose(), moves the end-effector into the starting position (cf. constants.JOINT_POSITION_START).

property name
property q
raise_error(self: panda_py._core.Panda) None

Raises a RuntimeError in Python when the robot has an active error. As panda-py controllers run asynchroneously, encountered errors don’t propagate to the proces’ main thread. Use this function or PandaContext to catch errors.

recover(self: panda_py._core.Panda) None
set_default_behavior(self: panda_py._core.Panda) None
start_controller(self: panda_py._core.Panda, controller: TorqueController) None
stop_controller(self: panda_py._core.Panda) None
teaching_mode(self: panda_py._core.Panda, active: bool, damping: numpy.ndarray[numpy.float64[7, 1]] = array([0., 0., 0., 0., 0., 0., 0.])) None
class panda_py.PandaContext

Bases: pybind11_object

property num_ticks
ok(self: panda_py._core.PandaContext) bool
property time
panda_py.fk(q: numpy.ndarray[numpy.float64[7, 1]]) numpy.ndarray[numpy.float64[4, 4]]

Computes end-effector pose in base frame from joint positions.

panda_py.ik(*args, **kwargs)

Overloaded function.

  1. ik(O_T_EE: numpy.ndarray[numpy.float64[4, 4]], q_init: numpy.ndarray[numpy.float64[7, 1]] = array([ 0. , -0.78539816, 0. , -2.35619449, 0. , 1.57079633, 0.78539816]), q_7: float = 0.7853981633974483) -> numpy.ndarray[numpy.float64[7, 1]]

    Compute analytical inverse kinematics. Solution is case consistent with configuration given in q_init.

    Args:
    O_T_EE: Homogeneous transform \(\mathbb{R}^{4\times 4}\) describing

    the end-effector pose.

    q_init: Reference joint positions, the result will be consistent

    with this configuration.

    q_7: Joint 7 is considered the redundant joint, use q_7 to set the

    desired joint position (default: \(\frac{\pi}{4}\)).

    Returns:

    Vector of shape (7,) containing joint positions.

  2. ik(position: numpy.ndarray[numpy.float64[3, 1]], orientation: numpy.ndarray[numpy.float64[4, 1]], q_init: numpy.ndarray[numpy.float64[7, 1]] = array([ 0. , -0.78539816, 0. , -2.35619449, 0. , 1.57079633, 0.78539816]), q_7: float = 0.7853981633974483) -> numpy.ndarray[numpy.float64[7, 1]]

    Same as ik() above, but takes position and orientation arguments.

panda_py.ik_full(*args, **kwargs)

Overloaded function.

  1. ik_full(O_T_EE: numpy.ndarray[numpy.float64[4, 4]], q_init: numpy.ndarray[numpy.float64[7, 1]] = array([ 0. , -0.78539816, 0. , -2.35619449, 0. , 1.57079633, 0.78539816]), q_7: float = 0.7853981633974483) -> numpy.ndarray[numpy.float64[4, 7]]

  2. ik_full(position: numpy.ndarray[numpy.float64[3, 1]], orientation: numpy.ndarray[numpy.float64[4, 1]], q_init: numpy.ndarray[numpy.float64[7, 1]] = array([ 0. , -0.78539816, 0. , -2.35619449, 0. , 1.57079633, 0.78539816]), q_7: float = 0.7853981633974483) -> numpy.ndarray[numpy.float64[4, 7]]

class panda_py.Desk(hostname: str, username: str, password: str, platform: str = 'panda')[source]

Bases: object

Connects to the control unit running the web-based Desk interface to manage the robot. Use this class to interact with the Desk from Python, e.g. if you use a headless setup. This interface supports common tasks such as unlocking the brakes, activating the FCI etc.

Newer versions of the system software use role-based access management to allow only one user to be in control of the Desk at a time. The controlling user is authenticated using a token. The Desk class saves those token in TOKEN_PATH and will use them when reconnecting to the Desk, retaking control. Without a token, control of a Desk can only be taken, if there is no active claim or the controlling user explicitly relinquishes control. If the controlling user’s token is lost, a user can take control forcefully (cf. Desk.take_control()) but needs to confirm physical access to the robot by pressing the circle button on the robot’s Pilot interface.

lock(force: bool = True) None[source]

Locks the brakes. API call blocks until the brakes are locked.

unlock(force: bool = True) None[source]

Unlocks the brakes. API call blocks until the brakes are unlocked.

reboot() None[source]

Reboots the robot hardware (this will close open connections).

activate_fci() None[source]

Activates the Franka Research Interface (FCI). Note that the brakes must be unlocked first. For older Desk versions, this function does nothing.

deactivate_fci() None[source]

Deactivates the Franka Research Interface (FCI). For older Desk versions, this function does nothing.

take_control(force: bool = False) bool[source]

Takes control of the Desk, generating a new control token and saving it. If force is set to True, control can be taken forcefully even if another user is already in control. However, the user will have to press the circle button on the robot’s Pilot within an alotted amount of time to confirm physical access.

For legacy versions of the Desk, this function does nothing.

release_control() None[source]

Explicitly relinquish control of the Desk. This will allow other users to take control or transfer control to the next user if there is an active queue of control requests.

static encode_password(username: str, password: str) bytes[source]

Encodes the password into the form needed to log into the Desk interface.

login() None[source]

Uses the object’s instance parameters to log into the Desk. The :py:class`Desk` class’s constructor will try to connect and login automatically.

logout() None[source]

Logs the current user out of the Desk. API calls will no longer be possible.

has_control() bool[source]
Returns:

True if this instance is in control of the Desk.

Return type:

bool

listen(cb: Callable[[Dict], None]) None[source]

Starts a thread listening to Pilot button events. All the Pilot buttons, except for the Pilot Mode button can be captured. Make sure Pilot Mode is set to Desk instead of End-Effector to receive direction key events. You can change the Pilot mode by pressing the Pilot Mode button or changing the mode in the Desk. Events will be triggered while buttons are pressed down or released.

Parameters:

cb – Callback fucntion that is called whenever a button event is received from the Desk. The callback receives a dict argument that contains the triggered buttons as keys. The values of those keys will depend on the kind of event, either True for a button pressed down or False when released. The possible buttons are: circle, cross, check, left, right, down, and up.

stop_listen() None[source]

Stop listener thread (cf. panda_py.Desk.listen()).

panda_py.TOKEN_PATH = '~/.panda_py/token.conf'

Path to the configuration file holding known control tokens. If Desk is used to connect to a control unit’s web interface and takes control, the generated token is stored in this file under the unit’s IP address or hostname.

Submodules