robots_pandapy
Franka robot interface via panda_py.
High-level interface for controlling Franka Emika Panda / FR3 robots via panda_py.
This module provides:
A thin wrapper class
Deskaroundpanda_py.Deskto manage Franka Desk operations such as unlocking/locking the robot, activating or deactivating the FCI, and taking or releasing control.- A high-level robot class
pandathat integrates: Franka-specific kinematic and dynamic specifications from
robotblockset.robot_spec(panda_spec,fr3_spec),Generic robot functionality from
robotblockset.robots.robot,Low-level control and state access via
panda_pyandpanda_py.libfranka,Controller implementations from
panda_py.controllers.
- A high-level robot class
The panda class offers:
Access to model quantities (Jacobian, gravity, Coriolis, inertia matrix).
Analytical forward and inverse kinematics for the Panda/FR3 kinematic chain.
Joint-space and Cartesian-space motion commands (JMove, CMove, GoTo_q, GoTo_T, GoTo_X).
Configuration and switching of control strategies (e.g. joint or Cartesian impedance).
Convenience methods for setting and querying Cartesian and joint compliance (stiffness, damping, “softness” factors).
Handling of collision behavior, contact and collision monitoring.
Management of the tool center point (TCP), stiffness frame, and external load properties consistent with Franka’s internal model.
The module is intended to be used as a higher-level abstraction on top of
panda_py, providing a more robotics-oriented, task-space–aware API that
integrates with the RobotBlockSet ecosystem.
- class robotblockset.franka.robots_pandapy.Desk(hostname: str = '192.168.3.100', username: str = 'user', password: str = 'password')[source]
Bases:
objectWrapper around
panda_py.Deskfor Franka Desk management.This helper connects to the robot control unit’s web-based Desk interface and exposes common remote operations such as locking or unlocking the brakes, activating or deactivating the FCI, and taking or releasing Desk control.
Recent Desk software versions allow only one user to control the Desk at a time. Control is mediated by a token managed internally by
panda_py.Desk.- Parameters:
hostname (str, optional) – IP address or hostname of the control unit running Franka Desk.
username (str, optional) – Username used to log into Franka Desk.
password (str, optional) – Password for the given Desk user.
Create a Desk client and log into the Franka Desk interface.
- Parameters:
hostname (str, optional) – IP address or hostname of the control unit running Franka Desk.
username (str, optional) – Username used to log into Franka Desk.
password (str, optional) – Password for the given Desk user.
- Returns:
This constructor initializes the Desk client in place.
- Return type:
None
- __init__(hostname: str = '192.168.3.100', username: str = 'user', password: str = 'password') None[source]
Create a Desk client and log into the Franka Desk interface.
- Parameters:
hostname (str, optional) – IP address or hostname of the control unit running Franka Desk.
username (str, optional) – Username used to log into Franka Desk.
password (str, optional) – Password for the given Desk user.
- Returns:
This constructor initializes the Desk client in place.
- Return type:
None
- Unlock() None[source]
Unlock the robot brakes.
This mirrors the
panda-unlockCLI behavior only partially. The CLI command unlocks the brakes and then activates the FCI, while this method only unlocks the brakes.
- Lock() None[source]
Lock the robot brakes.
This mirrors the
panda-lockCLI behavior only partially. The CLI command locks the brakes and then deactivates the FCI, while this method only locks the brakes.
- ActivateFCI() None[source]
Activate the Franka Research Interface (FCI).
The robot brakes must be unlocked first. On older Desk versions this operation has no effect.
- DeactivateFCI() None[source]
Deactivate the Franka Research Interface (FCI).
On older Desk versions this operation has no effect.
- TakeControl() None[source]
Take control of the Desk using the configured user credentials.
If another user already controls the Desk, forceful takeover requires confirmation of physical access on the robot’s Pilot interface. This wrapper uses the default non-forced takeover behavior.
- class robotblockset.franka.robots_pandapy.FrankaCollisionBehaviour[source]
Bases:
_structContainer for Franka collision and contact threshold settings.
Initialize collision threshold containers.
- class robotblockset.franka.robots_pandapy.FrankaDefaults[source]
Bases:
_structContainer for default Franka stiffness, damping, and collision settings.
Initialize default Franka compliance settings.
Initialize default Franka robot compliance and collision settings.
- class robotblockset.franka.robots_pandapy.panda(hostname: str = '192.168.3.100', name: str = 'panda', model: str = 'panda', control_strategy: str = 'JointImpedance', **kwargs: Any)[source]
Bases:
panda_spec,fr3_spec,robotHigh-level interface for Franka Emika Panda / FR3 robots via panda_py.
- Parameters:
hostname (str, optional) – IP address or hostname of the Panda / FR3 robot
name (str, optional) – Name identifier for the robot instance (default is ‘panda’)
model (str, optional) – Robot model, either ‘panda’ or ‘fr3’ (default is ‘panda’)
control_strategy (str, optional) – Initial control strategy to use. Default is
"JointImpedance".**kwargs (Any) – Additional keyword arguments passed to robot.__init__.
- Attributes:
hostname (str) – Robot controller hostname or IP address.
name (str) – Instance name used for logging and identification.
model (Any) – Active Franka model interface returned by panda_py.
panda (panda_py.Panda) – Low-level Panda robot client.
robot (Any) – Low-level robot interface returned by panda_py.
Create a Panda/FR3 robot interface backed by panda_py.
- Parameters:
hostname (str, optional) – Robot controller hostname or IP address.
name (str, optional) – Name used to identify the robot instance.
model (str, optional) – Franka robot model, either
"panda"or"fr3".control_strategy (str, optional) – Initial control strategy to activate after initialization.
**kwargs (Any) – Additional keyword arguments passed to robot.__init__.
- Returns:
This constructor initializes the Panda/FR3 robot interface in place.
- Return type:
None
- __init__(hostname: str = '192.168.3.100', name: str = 'panda', model: str = 'panda', control_strategy: str = 'JointImpedance', **kwargs: Any) None[source]
Create a Panda/FR3 robot interface backed by panda_py.
- Parameters:
hostname (str, optional) – Robot controller hostname or IP address.
name (str, optional) – Name used to identify the robot instance.
model (str, optional) – Franka robot model, either
"panda"or"fr3".control_strategy (str, optional) – Initial control strategy to activate after initialization.
**kwargs (Any) – Additional keyword arguments passed to robot.__init__.
- Returns:
This constructor initializes the Panda/FR3 robot interface in place.
- Return type:
None
- property J: ndarray
Jacobian matrix in joint space.
- Parameters:
frame (Union[str, int], optional) – Frame for which the Jacobian is evaluated. Supported string values are
"EE","Flange", and"Stiffness".state (Any, optional) – Robot state. If None, the current state is used.
- Returns:
Jacobian matrix in joint space.
- Return type:
JacobianType
- property c: ndarray
Coriolis and centrifugal joint torques.
- Parameters:
state (Any, optional) – The robot state. If None, the current state is used, by default None.
- Returns:
Coriolis and centrifugal joint torques.
- Return type:
JointTorqueType
- property g: ndarray
Gravitational joint torques
- Parameters:
state (Any, optional) – The robot state. If None, the current state is used, by default None.
- Returns:
Gravity joint torques.
- Return type:
JointTorqueType
- property H: ndarray
Inertia matrix H(q) in joint space.
- Parameters:
state (Any, optional) – The robot state. If None, the current state is used, by default None.
- Returns:
Symmetric inertia matrix in joint space.
- Return type:
np.ndarray
- FK(q: ndarray | None = None, out: str = 'x') ndarray[source]
Analytical forward kinematics of Panda robot.
- Parameters:
q (JointConfigurationType, optional) – Joint positions (nj, )
out (str, optional) – Output format for the result (pose, position, etc.), by default “x”.
- Returns:
End-effector pose in the output format requested by out.
- Return type:
Union[Pose3DType, HomogeneousMatrixType, Vector3DType, RotationMatrixType]
Notes
Assumes default TCP.
- IK(T: ndarray, q7: float = 0.7853981633974483, q_initial: ndarray | None = None) ndarray[source]
Analytical inverse kinematics of Panda robot.
- Parameters:
T (Union[Pose3DType, HomogeneousMatrixType]) – Target end-effector pose (7,) or (4, 4).
q7 (float, optional) – Desired angle for joint 7, by default np.pi / 4.
q_initial (JointConfigurationType, optional) – Initial guess for the joint positions (nj, ), by default None (uses home position).
- Returns:
Joint positions (nj, ) that achieve the desired end-effector pose.
- Return type:
JointConfigurationType
Notes
Assumes default TCP.
- GetState() None[source]
Update the cached robot state.
- Returns:
This method refreshes the internal state, command, and wrench caches.
- Return type:
None
- GoTo_q(q: ndarray, qdot: ndarray | None = None, trq: ndarray | None = None, wait: float | None = None, stiffness: ndarray | None = None, damping: ndarray | None = None, **kwargs: Any) int[source]
Update joint positions and wait
- Parameters:
q (JointConfigurationType) – desired joint positions (nj, )
qdot (JointVelocityType, optional) – desired joint velocities (nj, )
trq (JointTorqueType, optional) – additional joint torques (nj, )
wait (float, optional) – Maximal wait time since last update. Defaults to 0.
stiffness (JointConfigurationType, optional) – Desired joint stiffness (nj, )
damping (JointConfigurationType, optional) – Desired joint damping (nj, ).
- Returns:
Status of the move (0 for success, non-zero for error).
- Return type:
int
- GoTo_T(x: ndarray, v: ndarray | None = None, FT: ndarray | None = None, wait: float | None = None, **kwargs: Any) int[source]
Move the robot to the target pose and velocity in Cartesian space.
- Parameters:
x (Union[Pose3DType, HomogeneousMatrixType]) – Target end-effector pose in Cartesian space. Can be in different forms (e.g., Pose, Transformation matrix).
v (Velocity3DType, optional) – Target end-effector velocity in Cartesian space. Default is a zero velocity vector (6,).
FT (WrenchType, optional) – WrenchType, optional, NOT USED! Target force/torque in Cartesian space. Default is a zero wrench vector (6,).
wait (float, optional) – The time to wait after the movement, by default the sample time (self.tsamp).
**kwargs (dict) – Additional keyword arguments passed to other methods, including task_space.
- Returns:
The status of the move (0 for success, non-zero for error).
- Return type:
int
- Raises:
ValueError – If the provided task space is not supported.
Notes
The method first converts the input x, v, and FT based on the specified task space. The robot will be moved using Cartesian control.
- GoTo_X(x: ndarray, v: ndarray | None = None, FT: ndarray | None = None, wait: float | None = None, impedance: ndarray | List[float] | List[int] | Tuple[float, ...] | Tuple[int, ...] | None = None, damping: ndarray | List[float] | List[int] | Tuple[float, ...] | Tuple[int, ...] | None = None, R: ndarray | List[float] | List[int] | Tuple[float, ...] | Tuple[int, ...] | None = None, **kwargs: Any) int[source]
Update task pose and wait
The robot will be moved using Cartesian control.
- Parameters:
x (Union[Pose3DType, HomogeneousMatrixType]) – Target end-effector pose in Cartesian space. Can be in different forms (e.g., Pose, Transformation matrix).
v (Velocity3DType, optional) – Target end-effector velocity in Cartesian space. Default is a zero velocity vector (6,).
FT (WrenchType, optional) – WrenchType, optional, NOT USED! Target force/torque in Cartesian space. Default is a zero wrench vector (6,).
wait (float, optional) – The time to wait after the movement, by default the sample time (self.tsamp).
impedance (ArrayLike, optional) – The Cartesian impedance to set during the movement.
damping (ArrayLike, optional) – The Cartesian damping to set during the movement.
R (ArrayLike, optional) – The rotation matrix for impedance and damping directions, if applicable.
**kwargs (dict) – Additional keyword arguments for special use.
- Returns:
Status of the move (0 for success, non-zero for error).
- Return type:
int
- JMove(q: ndarray, t: float | None = None, vel: float | None = None, vel_fac: ndarray | None = None, wait: float | None = None, traj: str | None = None, added_trq: ndarray | None = None, min_joint_dist: float | None = None, asynchronous: bool = False, use_internal: bool | None = None, **kwargs: Any) Thread | int[source]
Moves the robot to a specified joint position with specified velocity and trajectory.
- Parameters:
q (JointConfigurationType) – Desired joint positions (nj,).
t (float, optional) – Time for the movement, by default None.
vel (float, optional) – Desired velocity for the movement, by default None.
vel_fac (JointConfigurationType, optional) – Velocity scaling factor for each joint, by default None.
wait (float, optional) – Time to wait after movement is completed, by default None.
traj (str, optional) – Trajectory type, by default None.
added_trq (JointTorqueType, optional) – Additional joint torques, by default None.
min_joint_dist (float, optional) – Minimum distance to target joint positions for movement execution, by default None.
asynchronous (bool, optional) – If True, executes the movement asynchronously, by default False.
use_internal (bool, optional) – If True, uses internal methods for movement execution, by default False.
**kwargs (dict) – Additional keyword arguments passed to internal methods.
- Returns:
The thread executing the asynchronous movement, or the status code if asynchronous is False.
- Return type:
Union[Thread, int]
Notes
If asynchronous is set to True, the movement will be executed in a separate thread.
The control strategy should be set to “Joint” for this function to work.
- CMove(x: ndarray, t: float | None = None, vel: float | None = None, vel_fac: float | None = None, traj: str | None = None, short: bool | None = None, wait: float | None = None, task_space: str | None = None, added_FT: ndarray | None = None, state: str = 'Commanded', min_pos_dist: float | None = None, min_ori_dist: float | None = None, asynchronous: bool = False, use_internal: bool | None = None, **kwargs: Any) Thread | int[source]
Executes a Cartesian move with specified target position, velocity, and trajectory.
The robot moves its end-effector to a target position with optional velocity, trajectory type, and additional force/torque settings.
- Parameters:
x (Union[Pose3DType, HomogeneousMatrixType, RotationMatrixType]) – The target Cartesian position (7,) or (4,4) or (3,3), where 7 represents position and orientation, and (4,4) is a homogeneous transformation matrix.
t (float, optional) – The duration for the movement, by default None.
vel (float, optional) – The velocity at which the end-effector moves, by default None.
vel_fac (float, optional) – A factor to scale the velocity, by default None.
traj (str, optional) – The trajectory type, by default None.
short (bool, optional) – Whether to shorten the path, by default None.
wait (float, optional) – The wait time after the movement, by default None.
task_space (str, optional) – The task space reference frame, by default None.
added_FT (WrenchType, optional) – Additional force/torque to be applied, by default None.
state (str, optional) – The state of the robot (e.g., “Commanded” or “Actual”), by default “Commanded”.
min_pos_dist (float, optional) – The minimum position distance for stopping, by default None.
min_ori_dist (float, optional) – The minimum orientation distance for stopping, by default None.
asynchronous (bool, optional) – Whether the motion should be performed asynchronously, by default False.
use_internal (bool, optional) – If True, uses internal methods for movement execution, by default False.
**kwargs (dict) – Additional keyword arguments passed to internal methods.
- Returns:
The thread executing the asynchronous movement, or the status code if synchronous.
- Return type:
Union[Thread, int]
- Raises:
ValueError – If an unsupported task space or parameter shape is provided.
- CheckContacts() bool[source]
Checks if a contact is ocurring on any of joint axes or the robot’s Cartesian axes.
- Returns:
True if a contact is detected, False otherwise.
- Return type:
bool
- GetCollisions() Tuple[ndarray, ndarray][source]
Returns the current joint and Cartesian collisions.
- Returns:
A tuple containing two lists: joint collisions and Cartesian collisions.
- Return type:
tuple
- GetContacts() Tuple[ndarray, ndarray][source]
Returns the current joint and Cartesian contacts.
- Returns:
A tuple containing two lists: joint contacts and Cartesian contacts.
- Return type:
tuple
- SetCollisionBehavior(tq: float | ndarray | None = None, F: float | ndarray | None = None, tq_low: float | ndarray | None = None, F_low: float | ndarray | None = None) None[source]
Sets the collision behavior.
- Parameters:
tq (Union[float, JointTorqueType], optional) – collision joint torque treshold [Nm], if None defualts are used. By default None
F (Union[float, WrenchType], optional) – collision task force treshold [N], if None defualts are used. By default None
tq_low (Union[float, JointTorqueType], optional) – lower collision joint torque treshold [Nm], by default None
F_low (Union[float, WrenchType], optional) – lower collision task force treshold [N], by default None
- Return type:
None
Notes
Forces or torques between lower and upper threshold are shown as contacts in the RobotState. Forces or torques above the upper threshold are registered as collision and cause the robot to stop moving.
- AvailableStrategies() List[str][source]
Returns a list of available control strategies for the robot.
- Returns:
A list of available control strategies.
- Return type:
List[str]
- SetStrategy(new_strategy: str) None[source]
Switch the active control strategy.
- Parameters:
new_strategy (str) – Name of the control strategy to activate.
- Returns:
This method activates the requested controller in place.
- Return type:
None
- Raises:
ValueError – If the specified strategy is not supported.
- TeachingMode(mode: bool, damping: ndarray | List[float] | List[int] | Tuple[float, ...] | Tuple[int, ...] | None = None) None[source]
Enable or disable gravity-compensated teaching mode.
In teaching mode the robot becomes compliant / backdrivable so that it can be guided by hand. Optionally, joint-space damping factors can be provided to adjust how easily each joint can be moved.
- Parameters:
mode (bool) – If True, enable teaching mode (robot is backdrivable and the current controller is paused). If False, disable teaching mode and restart the previously active controller.
damping (ArrayLike, optional) – Joint-space damping factors in the range [0, 1]. If a scalar is given, the same damping value is applied to all 7 joints. If an array is given, it must be a 7D vector specifying the damping factor per joint. If None, the default damping behavior of
panda_pyis used.
- Raises:
ValueError – If damping is provided but is neither a scalar nor a 7D vector.
Notes
Damping values are clipped to the interval [0, 1].
When
modeis set toFalse, this method callsResetCurrentTarget()and restarts the current controller viaself.panda.start_controller(self.ctrl).
- SetTeachMode() None[source]
Enable teach mode.
- Returns:
This method enables compliant hand-guiding mode.
- Return type:
None
- EndTeachMode() None[source]
Disable teach mode.
- Returns:
This method restores the standard robot control mode.
- Return type:
None
- GetCartesianCompliance() Tuple[ndarray, float, float][source]
Returns the current Cartesian compliance settings.
- Returns:
A tuple containing the Cartesian stiffness, damping ratio, and nullspace damping.
- Return type:
Tuple[np.ndarray, float, float]
- SetCartesianCompliance(impedance: ndarray | List[float] | List[int] | Tuple[float, ...] | Tuple[int, ...] | None = None, damping_ratio: float | None = None, nullspace_stiffness: float | None = None, hold_pose: bool = True) None[source]
Sets the Cartesian compliance settings.
- Parameters:
impedance (ArrayLike, optional) – The Cartesian impedance (stiffness) to set. Can be a 6D vector or a 6x6 matrix or 2D vector.
damping_ratio (float, optional) – The damping ratio to set.
nullspace_stiffness (float, optional) – The nullspace stiffness to set.
hold_pose (bool, optional) – If True, holds the current pose while setting compliance.
- Return type:
None
- GetCartesianStiffness() ndarray[source]
Returns the current Cartesian stiffness settings.
- Returns:
The current Cartesian stiffness settings.
- Return type:
np.ndarray
- SetCartesianStiffness(impedance: ndarray | List[float] | List[int] | Tuple[float, ...] | Tuple[int, ...] | None = None, hold_pose: bool = True) None[source]
Sets the Cartesian impedance settings.
- Parameters:
impedance (ArrayLike, optional) – The Cartesian impedance (stiffness) to set. Can be a 6D vector or a 6x6 matrix or 2D vector.
hold_pose (bool, optional) – If True, holds the current pose while setting compliance.
- Return type:
None
- GetCartesianDamping() float[source]
Returns the current Cartesian damping settings.
- Returns:
The current Cartesian damping settings.
- Return type:
float
- SetCartesianDamping(damping_ratio: float | None = None, hold_pose: bool = True) None[source]
Sets the Cartesian damping settings.
- Parameters:
damping_ratio (float, optional) – The damping ratio to set.
hold_pose (bool, optional) – If True, holds the current pose while setting compliance.
- Return type:
None
- SetCartesianSoft(stiffness: ndarray | List[float] | List[int] | Tuple[float, ...] | Tuple[int, ...], hold_pose: bool = True) None[source]
Sets the Cartesian stiffness to a fraction of the default stiffness. :param stiffness: The fraction of the default stiffness to set. Can be a scalar or a vector of shape (2,), shape (3,) or (6,). :type stiffness: ArrayLike :param hold_pose: If True, holds the current pose while setting compliance. :type hold_pose: bool, optional
- Return type:
None
Notes
If stiffness is a scalar, it is applied uniformly to all Cartesian axes.
If stiffness is a 2D vector, the first element is applied to the position axes and the second to the rotation axes.
If stiffness is a 3D vector, it is applied to both position and rotation axes.
The stiffness values are clipped between MinSoftnessForMotion and 1.0 before being applied.
- GetJointCompliance() Tuple[ndarray, ndarray][source]
Returns the current joint compliance settings.
- Returns:
A tuple containing the current joint stiffness and damping settings.
- Return type:
Tuple[np.ndarray, np.ndarray]
- SetJointCompliance(stiffness: ndarray | List[float] | List[int] | Tuple[float, ...] | Tuple[int, ...] | None = None, damping: ndarray | List[float] | List[int] | Tuple[float, ...] | Tuple[int, ...] | None = None, hold_pose: bool = True) None[source]
Sets the joint compliance settings.
- Parameters:
stiffness (ArrayLike, optional) – The joint stiffness to set. Can be a 7D vector or a scalar.
damping (ArrayLike, optional) – The joint damping to set. Can be a 7D vector or a scalar.
hold_pose (bool, optional) – If True, holds the current pose while setting compliance.
- Return type:
None
- GetJointStiffness() ndarray[source]
Returns the current joint stiffness settings.
- Returns:
The current joint stiffness settings.
- Return type:
np.ndarray
- SetJointStiffness(stiffness: ndarray | List[float] | List[int] | Tuple[float, ...] | Tuple[int, ...] | None = None, hold_pose: bool = True) None[source]
Sets the joint stiffness settings.
- Parameters:
stiffness (ArrayLike, optional) – The joint stiffness to set. Can be a 7D vector or a scalar.
hold_pose (bool, optional) – If True, holds the current pose while setting compliance.
- Return type:
None
- GetJointDamping() ndarray[source]
Returns the current joint damping settings.
- Returns:
The current joint damping settings.
- Return type:
np.ndarray
- SetJointDamping(damping: ndarray | List[float] | List[int] | Tuple[float, ...] | Tuple[int, ...] | None = None, hold_pose: bool = True) None[source]
Sets the joint damping settings.
- Parameters:
damping (ArrayLike, optional) – The joint damping to set. Can be a 7D vector or a scalar.
hold_pose (bool, optional) – If True, holds the current pose while setting compliance.
- Return type:
None
- SetJointSoft(stiffness_factor: ndarray | List[float] | List[int] | Tuple[float, ...] | Tuple[int, ...], hold_pose: bool = True) None[source]
Sets the joint stiffness to a fraction of the default stiffness.
- Parameters:
stiffness_factor (ArrayLike) – The fraction of the default stiffness to set. Can be a scalar or a 7D vector.
hold_pose (bool, optional) – If True, holds the current pose while setting compliance.
- Return type:
None
Notes
If stiffness is a scalar, it is applied uniformly to all joint axes.
The stiffness values are clipped between MinSoftnessForMotion and 1.0 before being applied.
- Update_tcp_from_franka_state() None[source]
Reads the currently set TCP in franka desk, uses it as default gripper TCP, and as the TCPin the robot object.
- Return type:
None
- SetTCP(tcp: ndarray | None = None, frame: str = 'Gripper') None[source]
Set the Tool Center Point (TCP) of the robot.
- Parameters:
tcp (TCPType, optional) – The transformation matrix or pose of the TCP. Default is the identity matrix.
frame (str, optional) – The frame to which the TCP is referenced. Can be “Gripper” or “Flange”. Default is “Gripper”.
- Return type:
None
- SetEEFrame(NE_T_EE: ndarray) None[source]
Sets the transformation $^{NE}T_{EE}$ from nominal end effector to end effector frame.
- Parameters:
NE_T_EE (HomogeneousMatrixType) – The transformation matrix from nominal end effector frame to end effector frame.
Notes
The transformation matrix is sent as a vectorized 4x4 matrix in column-major format.
- SetStiffnessFrame(EE_T_K: ndarray) None[source]
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 (HomogeneousMatrixType) – The transformation matrix from end effector frame to stiffness frame.
- Return type:
None
Notes
The transformation matrix is sent as a vectorized 4x4 matrix in column-major format.
- GetStiffnessFrame() ndarray[source]
Gets the transformation $^{EE}T_K$ from end effector frame to stiffness frame.
- Returns:
The transformation matrix from end effector frame to stiffness frame.
- Return type:
HomogeneousMatrixType
- SetLoad(load: load_params | None = None, mass: float | None = None, COM: ndarray | None = None, inertia: ndarray | None = None) None[source]
Set the load properties of the robot.
- Parameters:
load (load_params, optional) – The load object to be assigned, by default None.
mass (float, optional) – The mass of the load, by default None.
COM (Vector3DType, optional) – The center of mass of the load, by default None.
inertia (np.ndarray, optional) – The inertia of the load, by default None.
- Return type:
None
Notes
The center of mass is specified in the end effector frame. The inertia matrix should be provided in the end effector frame.
- isConnected() bool[source]
Checks if the robot is connected.
- Returns:
True if the robot is connected, False otherwise.
- Return type:
bool
- isReady() bool[source]
Check if the robot is ready for operations.
This method checks the _connected attribute to determine if the robot is connected and operational.
- Returns:
True if the robot is connected and ready for operations, otherwise False.
- Return type:
bool
- isActive() bool[source]
Check if the connection to robot is established.
- Returns:
Indicating if the connection to robot is established.
- Return type:
bool
- Check(silent: bool = False) List[str][source]
Checks the status of the robot.
- Parameters:
silent (bool, optional) – Present for API compatibility. It is currently not used.
- Returns:
List of active robot status conditions.
- Return type:
List[str]
- ErrorRecovery() int[source]
Recover the Panda robot from an error state.
- Returns:
Motion result code returned by the recovery routine.
- Return type:
int
Classes
|
Wrapper around |
Container for Franka collision and contact threshold settings. |
|
Container for default Franka stiffness, damping, and collision settings. |
|
|
High-level interface for Franka Emika Panda / FR3 robots via panda_py. |