robits.real.franka package
Submodules
robits.real.franka.control module
Control implementations for the Franka Panda robot.
This module provides concrete implementations of the control interfaces for the Franka Panda robot, including position control and Cartesian control. These controllers use the franky library to send commands to the robot hardware.
- class robits.real.franka.control.FrankyCartesianControl(robot_impl)
Bases:
ControllerBaseCartesian control for the Franka Panda robot.
This controller allows moving the robot’s end-effector in Cartesian space, specifying position and orientation. It supports both absolute and relative movements.
- Parameters:
robot_impl – The robot implementation to control
- start_controller()
Start the cartesian controller.
- stop_controller()
Stop the cartesian controller.
- update(pose: Tuple[ndarray, ndarray], relative=False)
Update the control target for the end-effector. Quaternions follow the xyzw format
- Parameters:
pose – A tuple containing the position and quaternion of the end effector.
relative – If True, updates the pose relative to the current state.
with robot.control(control_types.cartesian) as ctrl: ctrl.update((np.array([0.1, 0.2, 0.3]), np.array([0, 0, 0, 1])), relative=True)
- class robits.real.franka.control.FrankyControlManager(robot, default_joint_positions, **kwargs)
Bases:
ControlManagerManages control operations for the Franka Panda robot.
- Parameters:
robot – The robot instance to control.
default_joint_positions – The default joint positions for homing.
- move_home()
Move the robot to its home position.
- set_impedance_from_config(name='default')
Set impedance values from a predefined configuration.
- Parameters:
name – Name of the impedance configuration.
- set_joint_impedance(values)
Set the joint impedance values.
- Parameters:
values – List of impedance values for each joint.
- stop()
Stop the control manager. This is a default implementation
- class robits.real.franka.control.FrankyPositionControl(robot_impl)
Bases:
ControllerBasePosition control for the Franka panda robot.
- Parameters:
robot_impl – The robot implementation to control.
- start_controller()
Start the position controller.
- stop_controller()
Stop the position controller.
- update(joint_positions: ndarray, relative=False) None
Update the joint positions of the robot.
- Parameters:
joint_positions – The target joint angles as a numpy array
relative – If True, updates joint angles relative to current positions
- Raises:
ControlException – If the motion command fails
- Example:
- with robot.control(control_types.position) as ctrl:
# Move each joint 0.1 radians from current position ctrl.update(np.array([0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1]), relative=True)
robits.real.franka.franka_web_client module
copied from frankx.robot.Robot
See also
frankx.robot.Robot
robits.real.franka.gripper module
- class robits.real.franka.gripper.FrankaGripper(gripper_name: str, **kwargs)
Bases:
GripperBase- close()
Closes the gripper / hand
- classmethod get_gripper_type_name()
- get_info() Dict[str, Any]
Returns general information about the gripper.
- Returns:
Dictionary containing gripper information
- get_obs()
Gets the normalized position of the gripper / finger joints
- Returns:
A dictionary with joint positions and other observations
- property gripper_name
Returns the name of the gripper.
- Returns:
The gripper name
- property is_active
- is_open() bool
Returns whether the hand / gripper is open
- Returns:
True if the gripper is open
- property max_joint_position
Returns the maximum joint position of the gripper. Value is cached as reading the value takes a few milliseconds:
gripper.max_width:
45.8 ms ± 1.79 ms per loop (mean ± std. dev. of 7 runs, 100 loops each)
- property normalized_width
Returns the normalized width of the gripper. Unfortunately, reading the gripper width is slow. It can take some milliseconds to read the gripper width making it impractical in loops. Hence, the last value is cached using a decorator:
Reading the current gripper.width:
46.8 ms ± 2.11 ms per loop (mean ± std. dev. of 7 runs, 100 loops each)
- open()
Opens the gripper / hand
- set_pos(pos)
Set the open amount the gripper / hand
- Parameters:
pos – the normalized position
- robits.real.franka.gripper.timed_cache(time_delta=0.5)
robits.real.franka.robot module
- class robits.real.franka.robot.Franka(robot_name: str, transform_robot_to_world: Sequence[Sequence[float]], gripper: GripperBase | None = None, cameras: List[CameraBase] | None = None, audio: AudioBase | None = None, ip_addr: str = '172.16.0.2', dynamics_factor: float = 0.2, **kwargs)
Bases:
UnimanualRobotRobot implementation for the Franka Panda robot using franky.
This class provides a concrete implementation of the RoBits robot interface for controlling a physical Franka Panda robot arm. It establishes connection to the robot hardware and integrates with gripper and camera components.
The implementation uses the franky library for low-level communication with the robot controller and exposes a high-level interface for robot control.
- connect_to_robot() franky.Robot
Connect to the physical Franka robot sing the franky library. Configures real-time behavior based on system capabilities and sets up initial safety parameters.
- Returns:
Initialized FrankyRobot instance ready for control
- Raises:
ControlException if connection fails
- control_arm(action: CartesianAction, auto_recover=True)
Control the robot arm to move to a specified Cartesian pose.
Moves the robot’s end-effector to the position and orientation specified in the CartesianAction. The movement is safety-checked using the check_bounds decorator.
- Parameters:
action – CartesianAction specifying target position and orientation
auto_recover – Whether to automatically recover from errors
- Returns:
True if movement succeeded, False otherwise
- control_hand(action: CartesianAction)
- property eef_matrix
The 4x4 matrix of the current end-effector pose
- Returns:
The pose of the robot as matrix
- property eef_pose
The pose of the end-effector as (position, quaternion). Quaternion format is xyzw
- Returns:
The pose of the robot as tuple
- get_info()
- get_proprioception_data(include_eef=True, include_gripper_obs=True) Dict[str, Any]
Gets the proprioception data from a robot. This includes
joint position
joint velocities
gripper joint position (optional)
gripper pose (optional)
- Parameters:
include_eef – include pose of the end-effector
include_gripper_obs – include joint positions and other proprioception of the gripper
- Returns:
The proprioception data
- property robot_name: str
Returns the name of the robot.
- Returns:
The robot name