panda_py.controllers module

Control library for the Panda robot. The general workflow is to instantiate a controller and hand it over to the panda_py.Panda class for execution using the function panda_py.Panda.start_controller().

class panda_py.controllers.TorqueController

Bases: pybind11_object

Base class for all torque controllers. Torque controllers provide the robot with torques at 1KHz and the user with an asynchronous interface to provide control signals.

get_time(self: panda_py._core.TorqueController) float

Get time in seconds since this controller was started.

class panda_py.controllers.CartesianImpedance(self: panda_py._core.CartesianImpedance, impedance: numpy.ndarray[numpy.float64[6, 6]] = array([[600., 0., 0., 0., 0., 0.], [0., 600., 0., 0., 0., 0.], [0., 0., 600., 0., 0., 0.], [0., 0., 0., 30., 0., 0.], [0., 0., 0., 0., 30., 0.], [0., 0., 0., 0., 0., 30.]]), damping_ratio: float = 1.0, nullspace_stiffness: float = 0.5, filter_coeff: float = 1.0)

Bases: TorqueController

Cartesian impedance controller. Takes the end-effector pose in robot base frame, as well as desired nullspace joint positions as input.

Parameters:
  • impedance – Cartesian impedance expressed as a matrix \(\in \mathbb{R}^{6\times 6}\).

  • damping_ratio – Cartesian damping is computed based on the given impedance and damping ratio.

  • nullspace_stiffness – Control gain of the nullspace term.

  • filter_coeff – TP1 filter coefficient used to filter input signals.

set_control(self: panda_py._core.CartesianImpedance, position: numpy.ndarray[numpy.float64[3, 1]], orientation: numpy.ndarray[numpy.float64[4, 1]], q_nullspace: numpy.ndarray[numpy.float64[7, 1]] = array([0., -0.78539816, 0., -2.35619449, 0., 1.57079633, 0.78539816])) None
set_damping_ratio(self: panda_py._core.CartesianImpedance, damping: float) None
set_filter(self: panda_py._core.CartesianImpedance, filter_coeff: float) None
set_impedance(self: panda_py._core.CartesianImpedance, impedance: numpy.ndarray[numpy.float64[6, 6]]) None
set_nullspace_stiffness(self: panda_py._core.CartesianImpedance, nullspace_stiffness: float) None
class panda_py.controllers.IntegratedVelocity(self: panda_py._core.IntegratedVelocity, 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.]))

Bases: TorqueController

get_qd(self: panda_py._core.IntegratedVelocity) numpy.ndarray[numpy.float64[7, 1]]
set_control(self: panda_py._core.IntegratedVelocity, velocity: numpy.ndarray[numpy.float64[7, 1]]) None
set_damping(self: panda_py._core.IntegratedVelocity, damping: numpy.ndarray[numpy.float64[7, 1]]) None
set_stiffness(self: panda_py._core.IntegratedVelocity, stiffness: numpy.ndarray[numpy.float64[7, 1]]) None
class panda_py.controllers.JointPosition(self: panda_py._core.JointPosition, 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.]), filter_coeff: float = 1.0)

Bases: TorqueController

set_control(self: panda_py._core.JointPosition, position: numpy.ndarray[numpy.float64[7, 1]], velocity: numpy.ndarray[numpy.float64[7, 1]] = array([0., 0., 0., 0., 0., 0., 0.])) None
set_damping(self: panda_py._core.JointPosition, damping: numpy.ndarray[numpy.float64[7, 1]]) None
set_filter(self: panda_py._core.JointPosition, filter_coeff: float) None
set_stiffness(self: panda_py._core.JointPosition, stiffness: numpy.ndarray[numpy.float64[7, 1]]) None
class panda_py.controllers.AppliedTorque(self: panda_py._core.AppliedTorque, damping: numpy.ndarray[numpy.float64[7, 1]] = array([0., 0., 0., 0., 0., 0., 0.]), filter_coeff: float = 1.0)

Bases: TorqueController

set_control(self: panda_py._core.AppliedTorque, torque: numpy.ndarray[numpy.float64[7, 1]]) None
set_damping(self: panda_py._core.AppliedTorque, damping: numpy.ndarray[numpy.float64[7, 1]]) None
set_filter(self: panda_py._core.AppliedTorque, filter_coeff: float) None
class panda_py.controllers.AppliedForce(self: panda_py._core.AppliedForce, damping: numpy.ndarray[numpy.float64[7, 1]] = array([0., 0., 0., 0., 0., 0., 0.]), filter_coeff: float = 1.0)

Bases: TorqueController

set_control(self: panda_py._core.AppliedForce, force: numpy.ndarray[numpy.float64[6, 1]]) None
set_damping(self: panda_py._core.AppliedForce, damping: numpy.ndarray[numpy.float64[7, 1]]) None
set_filter(self: panda_py._core.AppliedForce, filter_coeff: float) None
class panda_py.controllers.Force(self: panda_py._core.Force, k_p: float = 1.0, k_i: float = 2.0, damping: numpy.ndarray[numpy.float64[7, 1]] = array([1., 1., 1., 1., 0.33, 0.33, 0.17]), threshold: float = 0.01, filter_coeff: float = 0.001)

Bases: TorqueController

property name
set_control(self: panda_py._core.Force, force: numpy.ndarray[numpy.float64[3, 1]]) None
set_filter(self: panda_py._core.Force, filter_coeff: float) None
set_integral_gain(self: panda_py._core.Force, k_i: float) None
set_proportional_gain(self: panda_py._core.Force, k_p: float) None