Robot#
The Robot class maintains a network connection to the robot, provides the current robot state, gives access to the model library and allows to control the robot.
Class Definition#
- class pylibfranka.Robot#
Bases:
pybind11_objectMain interface for controlling a Franka robot.
Provides real-time control capabilities including torque, position, and velocity control modes.
- automatic_error_recovery(self: pylibfranka._pylibfranka.Robot) None#
Attempt automatic error recovery.
- load_model(self: pylibfranka._pylibfranka.Robot) pylibfranka._pylibfranka.Model#
Load robot dynamics model.
@return Model object for computing dynamics quantities
- read_once(self: pylibfranka._pylibfranka.Robot) pylibfranka._pylibfranka.RobotState#
Read current robot state once.
@return Current robot state
- set_EE(self: pylibfranka._pylibfranka.Robot, arg0: List[float[16]]) None#
Set end effector frame relative to nominal end effector frame.
@param NE_T_EE Homogeneous transformation matrix (16,) in column-major order
- set_K(self: pylibfranka._pylibfranka.Robot, arg0: List[float[16]]) None#
Set stiffness frame K in end effector frame.
@param EE_T_K Homogeneous transformation matrix (16,) in column-major order
- set_cartesian_impedance(self: pylibfranka._pylibfranka.Robot, arg0: List[float[6]]) None#
Set Cartesian impedance for internal controller.
@param K_x Cartesian stiffness values [N/m, Nm/rad] (6,)
- set_collision_behavior(self: pylibfranka._pylibfranka.Robot, arg0: List[float[7]], arg1: List[float[7]], arg2: List[float[6]], arg3: List[float[6]]) None#
Configure collision detection thresholds.
@param lower_torque_thresholds Lower torque thresholds [Nm] (7,) @param upper_torque_thresholds Upper torque thresholds [Nm] (7,) @param lower_force_thresholds Lower Cartesian force thresholds [N, Nm] (6,) @param upper_force_thresholds Upper Cartesian force thresholds [N, Nm] (6,)
- set_joint_impedance(self: pylibfranka._pylibfranka.Robot, arg0: List[float[7]]) None#
Set joint impedance for internal controller.
@param K_theta Joint stiffness values [Nm/rad] (7,)
- set_load(self: pylibfranka._pylibfranka.Robot, arg0: float, arg1: List[float[3]], arg2: List[float[9]]) None#
Set external load parameters.
@param load_mass Mass of the external load [kg] @param F_x_Cload Center of mass of load in flange frame [m] (3,) @param load_inertia Inertia tensor of load [kg*m²] (9,) in column-major order
- start_cartesian_pose_control(self: pylibfranka._pylibfranka.Robot, arg0: pylibfranka._pylibfranka.ControllerMode) pylibfranka._pylibfranka.ActiveControlBase#
Start Cartesian pose control mode.
@param control_type Controller mode (JointImpedance or CartesianImpedance) @return ActiveControlBase interface for sending Cartesian pose commands
- start_joint_position_control(self: pylibfranka._pylibfranka.Robot, arg0: pylibfranka._pylibfranka.ControllerMode) pylibfranka._pylibfranka.ActiveControlBase#
Start joint position control mode.
@param control_type Controller mode (JointImpedance or CartesianImpedance) @return ActiveControlBase interface for sending position commands
- start_joint_velocity_control(self: pylibfranka._pylibfranka.Robot, arg0: pylibfranka._pylibfranka.ControllerMode) pylibfranka._pylibfranka.ActiveControlBase#
Start joint velocity control mode.
@param control_type Controller mode (JointImpedance or CartesianImpedance) @return ActiveControlBase interface for sending velocity commands
- start_torque_control(self: pylibfranka._pylibfranka.Robot) pylibfranka._pylibfranka.ActiveControlBase#
Start torque control mode.
@return ActiveControlBase interface for sending torque commands
- stop(self: pylibfranka._pylibfranka.Robot) None#
Stop currently running motion.
Constructor#
- pylibfranka.Robot(robot_ip_address, realtime_config=RealtimeConfig.kEnforce)
Establishes a connection with the robot.
- Parameters:
robot_ip_address (str) – IP address or hostname of the robot controller
realtime_config (RealtimeConfig) – Real-time scheduling requirements. Default:
RealtimeConfig.kEnforce
- Raises:
NetworkException – if the connection cannot be established
IncompatibleVersionException – if the robot’s software version is incompatible
Example:
import pylibfranka # Connect with real-time enforcement robot = pylibfranka.Robot("172.16.0.2") # Connect without real-time enforcement (for testing) robot_test = pylibfranka.Robot( "172.16.0.2", pylibfranka.RealtimeConfig.kIgnore )
Control Methods#
start_torque_control#
- Robot.start_torque_control()
Starts a new torque controller.
- Returns:
Active control interface for sending torque commands
- Return type:
- Raises:
ControlException – if an error related to torque control occurred
InvalidOperationException – if a conflicting operation is already running
NetworkException – if the connection is lost, e.g. after a timeout
Example:
robot = pylibfranka.Robot("172.16.0.2") # Start torque control mode (gravity is automatically compensated) control = robot.start_torque_control() # Control loop at 1 kHz for i in range(5000): state, duration = control.readOnce() # Send zero torque for compliant mode tau = pylibfranka.Torques([0, 0, 0, 0, 0, 0, 0]) # Send torque command control.writeOnce(tau)
See also
ActiveControlBase.writeOnce()for sending torque commands
start_joint_position_control#
- Robot.start_joint_position_control(control_type)
Starts a new joint position motion generator.
- Parameters:
control_type (ControllerMode) – Controller mode for the operation
- Returns:
Active control interface for sending position commands
- Return type:
- Raises:
ControlException – if an error related to motion generation occurred
InvalidOperationException – if a conflicting operation is already running
NetworkException – if the connection is lost, e.g. after a timeout
start_joint_velocity_control#
- Robot.start_joint_velocity_control(control_type)
Starts a new joint velocity motion generator.
- Parameters:
control_type (ControllerMode) – Controller mode for the operation
- Returns:
Active control interface for sending velocity commands
- Return type:
- Raises:
ControlException – if an error related to motion generation occurred
InvalidOperationException – if a conflicting operation is already running
NetworkException – if the connection is lost, e.g. after a timeout
State and Model#
read_once#
- Robot.read_once()
Read current robot state once.
- Returns:
Current robot state containing all state information
- Return type:
- Raises:
NetworkException – if the connection is lost
load_model#
- Robot.load_model()
Load robot dynamics model.
- Returns:
Model object for computing dynamics quantities
- Return type:
Configuration Methods#
set_collision_behavior#
- Robot.set_collision_behavior(lower_torque_thresholds, upper_torque_thresholds, lower_force_thresholds, upper_force_thresholds)
Configure collision detection thresholds.
- Parameters:
lower_torque_thresholds (array_like) – Lower torque thresholds [Nm] for each joint (7,)
upper_torque_thresholds (array_like) – Upper torque thresholds [Nm] for each joint (7,)
lower_force_thresholds (array_like) – Lower Cartesian force thresholds [N, Nm] (6,)
upper_force_thresholds (array_like) – Upper Cartesian force thresholds [N, Nm] (6,)
- Raises:
CommandException – if the Control reports an error
NetworkException – if the connection is lost
set_joint_impedance#
- Robot.set_joint_impedance(K_theta)
Sets the impedance for each joint in the internal controller.
User-provided torques are not affected by this setting.
- Parameters:
K_theta (array_like) – Joint impedance values \(K_{\theta_{1-7}} \in [0, 14250]\) [Nm/rad] (7,)
- Raises:
CommandException – if the Control reports an error
NetworkException – if the connection is lost
set_cartesian_impedance#
- Robot.set_cartesian_impedance(K_x)
Sets the Cartesian impedance for the internal controller.
User-provided torques are not affected by this setting.
- Parameters:
K_x (array_like) – Cartesian impedance values [N/m, Nm/rad] for (x, y, z, roll, pitch, yaw) (6,)
- Raises:
CommandException – if the Control reports an error
NetworkException – if the connection is lost
set_K#
- Robot.set_K(EE_T_K)
Sets the transformation \(^{EE}T_K\) from end effector frame to stiffness frame.
The transformation matrix is represented as a vectorized 4x4 matrix in column-major format.
- Parameters:
EE_T_K (array_like) – Vectorized EE-to-K transformation matrix \(^{EE}T_K\), column-major (16,)
- Raises:
CommandException – if the Control reports an error
NetworkException – if the connection is lost
set_EE#
- Robot.set_EE(NE_T_EE)
Sets the transformation \(^{NE}T_{EE}\) from nominal end effector to end effector frame.
The transformation matrix is represented as a vectorized 4x4 matrix in column-major format.
- Parameters:
NE_T_EE (array_like) – Vectorized NE-to-EE transformation matrix \(^{NE}T_{EE}\), column-major (16,)
- Raises:
CommandException – if the Control reports an error
NetworkException – if the connection is lost
See also
RobotState.NE_T_EEfor end effector pose in nominal end effector frameRobotState.O_T_EEfor end effector pose in world base frameRobotState.F_T_EEfor end effector pose in flange frame
set_load#
- Robot.set_load(load_mass, F_x_Cload, load_inertia)
Sets dynamic parameters of a payload.
Note
This is not for setting end effector parameters, which have to be set in the administrator’s interface.
- Parameters:
load_mass (float) – Mass of the load [kg]
F_x_Cload (array_like) – Translation from flange to center of mass of load \(^Fx_{C_{load}}\) [m] (3,)
load_inertia (array_like) – Inertia matrix \(I_{load}\) [kg·m²], column-major (9,)
- Raises:
CommandException – if the Control reports an error
NetworkException – if the connection is lost
Error Handling#
automatic_error_recovery#
- Robot.automatic_error_recovery()
Attempt automatic error recovery.
Executes automatic error recovery if the robot is in an error state. This can clear recoverable errors.
- Raises:
CommandException – if recovery fails
NetworkException – if the connection is lost
stop#
- Robot.stop()
Stops all currently running motions.
If a control or motion generator loop is running in another thread, it will be preempted with a
ControlException.- Raises:
CommandException – if the Control reports an error
NetworkException – if the connection is lost
See Also#
ActiveControlBase– Control interface returned by start_* methodsRobotState– Robot state data structureModel– Dynamics model for computing kinematics and dynamicsErrors– Robot error state information