Python API Documentation

A more unified interface class combining the functionalities of all separate classes of Franka ROS Interface is available at Panda Robot.

Code Quality

franka_interface

ArmInterface

  • Interface class that can monitor and control the robot
  • Provides all required information about robot state and end-effector state
  • Joint positions, velocities, and effort can be directly controlled and monitored using available methods
  • Smooth interpolation of joint positions possible
  • End-effector and Stiffness frames can be directly set (uses FrankaFramesInterface from franka_ros_interface/franka_tools)
  • All functionalities of ArmInterface can also be accessed using the more unified PandaArm class defined in the Panda Robot package.
class franka_interface.ArmInterface(synchronous_pub=False)[source]

Bases: object

Interface Class for an arm of Franka Panda robot. Constructor.

Parameters:synchronous_pub (bool) –

designates the JointCommand Publisher as Synchronous if True and Asynchronous if False.

Synchronous Publishing means that all joint_commands publishing to the robot’s joints will block until the message has been serialized into a buffer and that buffer has been written to the transport of every current Subscriber. This yields predicable and consistent timing of messages being delivered from this Publisher. However, when using this mode, it is possible for a blocking Subscriber to prevent the joint_command functions from exiting. Unless you need exact JointCommand timing, default to Asynchronous Publishing (False).

class RobotMode[source]

Bases: enum.IntEnum

Enum class for specifying and retrieving the current robot mode.

coriolis_comp()[source]

Return coriolis compensation torques. Useful for compensating coriolis when performing direct torque control of the robot.

Return type:np.ndarray
Returns:7D joint torques compensating for coriolis.
endpoint_effort(in_base_frame=True)[source]

Return Cartesian endpoint wrench {force, torque}.

Parameters:in_base_frame (bool) – if True, returns end-effector effort with respect to base frame, else in stiffness frame [default: True]
Return type:dict({str:np.ndarray (shape:(3,)),str:np.ndarray (shape:(3,))})
Returns:force and torque at endpoint as named tuples in a dict in the base frame of the robot or in the stiffness frame (wrist)
  • ’force’: Cartesian force on x,y,z axes in np.ndarray format
  • ’torque’: Torque around x,y,z axes in np.ndarray format
endpoint_pose()[source]

Return Cartesian endpoint pose {position, orientation}.

Return type:dict({str:np.ndarray (shape:(3,)), str:quaternion.quaternion})
Returns:position and orientation as named tuples in a dict
  • ’position’: np.array of x, y, z
  • ’orientation’: quaternion x,y,z,w in quaternion format
endpoint_velocity()[source]

Return Cartesian endpoint twist {linear, angular}.

Return type:dict({str:np.ndarray (shape:(3,)),str:np.ndarray (shape:(3,))})
Returns:linear and angular velocities as named tuples in a dict
  • ’linear’: np.array of x, y, z
  • ’angular’: np.array of x, y, z (angular velocity along the axes)
error_in_current_state()[source]

Return True if the specified limb has experienced an error.

Return type:bool
Returns:True if the arm has error, False otherwise.
exit_control_mode(timeout=5, velocity_tolerance=0.01)[source]

Clean exit from advanced control modes (joint torque or velocity). Resets control to joint position mode with current positions until further advanced control commands are sent to the robot.

Note

In normal cases, this method is not required as the interface automatically switches to position control mode if advanced control commands (velocity/torque) are not sent at regular intervals. Therefore it is enough to stop sending the commands to disable advanced control modes.

Note

In sim, this method does nothing.

Parameters:
  • timeout (float) – seconds to wait for robot to stop moving before giving up [default: 5]
  • velocity_tolerance (float) – tolerance
get_controller_manager()[source]
Returns:the FrankaControllerManagerInterface instance associated with the robot.
Return type:franka_tools.FrankaControllerManagerInterface
get_flange_pose(pos=None, ori=None)[source]

Get the pose of flange (panda_link8) given the pose of the end-effector frame.

Note

In sim, this method does nothing.

Parameters:
  • pos (np.ndarray, optional) – position of the end-effector frame in the robot’s base frame, defaults to current end-effector position
  • ori (quaternion.quaternion, optional) – orientation of the end-effector frame, defaults to current end-effector orientation
Returns:

corresponding flange frame pose in the robot’s base frame

Return type:

np.ndarray, quaternion.quaternion

get_frames_interface()[source]
Returns:the FrankaFramesInterface instance associated with the robot.
Return type:franka_tools.FrankaFramesInterface
get_joint_limits()[source]

Return the joint limits (defined in the parameter server)

Return type:franka_core_msgs.msg.JointLimits
Returns:JointLimits
get_movegroup_interface()[source]
Returns:the movegroup interface instance associated with the robot.
Return type:franka_moveit.PandaMoveGroupInterface
get_robot_params()[source]
Returns:Useful parameters from the ROS parameter server.
Return type:franka_interface.RobotParams
get_robot_status()[source]

Return dict with all robot status information.

Return type:dict
Returns:[‘robot_mode’ (RobotMode object), ‘robot_status’ (bool), ‘errors’ (dict() of errors and their truth value), ‘error_in_curr_status’ (bool)]
gravity_comp()[source]

Return gravity compensation torques.

Return type:np.ndarray
Returns:7D joint torques compensating for gravity.
has_collided()[source]

Returns true if either joint collision or cartesian collision is detected. Collision thresholds can be set using instance of franka_tools.CollisionBehaviourInterface.

in_safe_state()[source]

Return True if the specified limb is in safe state (no collision, reflex, errors etc.).

Return type:bool
Returns:True if the arm is in safe state, False otherwise.
joint_angle(joint)[source]

Return the requested joint angle.

Parameters:joint (str) – name of a joint
Return type:float
Returns:angle in radians of individual joint
joint_angles()[source]

Return all joint angles.

Return type:dict({str:float})
Returns:unordered dict of joint name Keys to angle (rad) Values
joint_effort(joint)[source]

Return the requested joint effort.

Parameters:joint (str) – name of a joint
Return type:float
Returns:effort in Nm of individual joint
joint_efforts()[source]

Return all joint efforts.

Return type:dict({str:float})
Returns:unordered dict of joint name Keys to effort (Nm) Values
joint_inertia_matrix()[source]

Returns the current joint inertia matrix given by libfranka.

Returns:joint inertia matrix (7,7)
Return type:np.ndarray [7x7]
joint_names()[source]

Return the names of the joints for the specified limb.

Return type:[str]
Returns:ordered list of joint names from proximal to distal (i.e. shoulder to wrist).
joint_ordered_angles()[source]

Return all joint angles.

Return type:[float]
Returns:joint angles (rad) orded by joint_names from proximal to distal (i.e. shoulder to wrist).
joint_velocities()[source]

Return all joint velocities.

Return type:dict({str:float})
Returns:unordered dict of joint name Keys to velocity (rad/s) Values
joint_velocity(joint)[source]

Return the requested joint velocity.

Parameters:joint (str) – name of a joint
Return type:float
Returns:velocity in radians/s of individual joint
move_to_cartesian_pose(pos, ori=None, use_moveit=True)[source]

Move robot end-effector to specified cartesian pose using MoveIt! (also avoids obstacles if they are defined using franka_moveit.ExtendedPlanningSceneInterface)

Parameters:
  • pos ([float] or np.ndarray) – target end-effector position
  • ori (quaternion.quaternion or [float] (quaternion in w,x,y,z order), optional) – target orientation quaternion for end-effector, defaults to current ori
  • use_moveit (bool, optional) – Flag for using MoveIt (redundant for now; only works if set to True), defaults to True
move_to_joint_positions(positions, timeout=10.0, threshold=0.00085, test=None, use_moveit=True)[source]

(Blocking) Commands the limb to the provided positions. Waits until the reported joint state matches that specified. This function uses a low-pass filter using JointTrajectoryService to smooth the movement or optionally uses MoveIt! to plan and execute a trajectory.

Parameters:
  • positions (dict({str:float})) – joint_name:angle command
  • timeout (float) – seconds to wait for move to finish [15]
  • threshold (float) – position threshold in radians across each joint when move is considered successful [0.00085]
  • test – optional function returning True if motion must be aborted
  • use_moveit (bool) – if set to True, and movegroup interface is available, move to the joint positions using moveit planner.
move_to_neutral(timeout=15.0, speed=0.15)[source]

Command the Limb joints to a predefined set of “neutral” joint angles. From rosparam /franka_control/neutral_pose.

Parameters:
  • timeout (float) – seconds to wait for move to finish [15]
  • speed (float) – ratio of maximum joint speed for execution default= 0.15; range= [0.0-1.0]
pause_controllers_and_do(func, *args, **kwargs)[source]

Temporarily stops all active controllers and calls the provided function before restarting the previously active controllers.

Parameters:func (callable) – the function to be called
reset_EE_frame()[source]

Reset EE frame to default. (defined by FrankaFramesInterface.DEFAULT_TRANSFORMATIONS.EE_FRAME global variable defined in franka_tools.FrankaFramesInterface source code). By default, this resets to align with the nominal-end effector frame (F_T_NE) in the flange frame.

Return type:[bool, str]
Returns:[success status of service request, error msg if any]
set_EE_at_frame(frame_name, timeout=5.0)[source]

Set new EE frame to the same frame as the link frame given by ‘frame_name’. Motion controllers are stopped and restarted for switching

Parameters:frame_name (str) – desired tf frame name in the tf tree
Return type:[bool, str]
Returns:[success status of service request, error msg if any]
set_EE_frame(frame)[source]

Set new EE frame based on the transformation given by ‘frame’, which is the transformation matrix defining the new desired EE frame with respect to the nominal end-effector frame (NE_T_EE). Motion controllers are stopped and restarted for switching.

Parameters:frame ([float (16,)] / np.ndarray (4x4)) – transformation matrix of new EE frame wrt nominal end-effector frame (column major)
Return type:[bool, str]
Returns:[success status of service request, error msg if any]
set_collision_threshold(cartesian_forces=None, joint_torques=None)[source]

Set Force Torque thresholds for deciding robot has collided.

Returns:

True if service call successful, False otherwise

Return type:

bool

Parameters:
  • cartesian_forces ([float] size 6) – Cartesian force threshold for collision detection [x,y,z,R,P,Y] (robot motion stops if violated)
  • joint_torques ([float] size 7) – Joint torque threshold for collision (robot motion stops if violated)
set_command_timeout(timeout)[source]

Set the timeout in seconds for the joint controller. Advanced control commands (vel, torque) should be sent within this time, or else the controller will switch back to default control mode.

Parameters:timeout (float) – timeout in seconds
set_joint_position_speed(speed=0.3)[source]

Set ratio of max joint speed to use during joint position moves (only for move_to_joint_positions).

Set the proportion of maximum controllable velocity to use during joint position control execution. The default ratio is 0.3, and can be set anywhere from [0.0-1.0] (clipped). Once set, a speed ratio will persist until a new execution speed is set.

Parameters:speed (float) – ratio of maximum joint speed for execution default= 0.3; range= [0.0-1.0]
set_joint_positions(positions)[source]

Commands the joints of this limb to the specified positions.

Parameters:positions (dict({str:float}) – dict of {‘joint_name’:joint_position,}
set_joint_positions_velocities(positions, velocities)[source]

Commands the joints of this limb using specified positions and velocities using impedance control. Command at time t is computed as:

\(u_t= coriolis\_factor * coriolis\_t + K\_p * (positions - curr\_positions) + K\_d * (velocities - curr\_velocities)\)

Parameters:
  • positions ([float]) – desired joint positions as an ordered list corresponding to joints given by self.joint_names()
  • velocities ([float]) – desired joint velocities as an ordered list corresponding to joints given by self.joint_names()
set_joint_torques(torques)[source]

Commands the joints of this limb with the specified torques.

Parameters:torques (dict({str:float})) – dict of {‘joint_name’:joint_torque,}
set_joint_velocities(velocities)[source]

Commands the joints of this limb to the specified velocities.

Parameters:velocities (dict({str:float})) – dict of {‘joint_name’:joint_velocity,}
tip_states()[source]

Return Cartesian endpoint state for a given tip name

Return type:TipState object
Returns:pose, velocity, effort, effort_in_K_frame
what_errors()[source]

Return list of error messages if there is error in robot state

Return type:[str]
Returns:list of names of current errors in robot state
zero_jacobian()[source]

Returns the current jacobian matrix given by libfranka.

Returns:end-effector jacobian (6,7)
Return type:np.ndarray [6x7]

GripperInterface

  • Interface class to monitor and control gripper
  • Gripper open, close methods
  • Grasp, move joints methods
class franka_interface.GripperInterface(gripper_joint_names=('panda_finger_joint1', 'panda_finger_joint2'), calibrate=False, **kwargs)[source]

Bases: object

Interface class for the gripper on the Franka Panda robot.

Parameters:
  • gripper_joint_names ([str]) – Names of the finger joints
  • ns (str) – base namespace of interface (‘frank_ros_interface’/’panda_simulator’)
  • calibrate (bool) – Attempts to calibrate the gripper when initializing class (defaults True)
close()[source]

close gripper to till collision is detected. Note: This is not exactly doing what it should. The behaviour is faked by catching the error thrown when trying to grasp a very small object with a very small force. Since the gripper will actually hit the object before it reaches the commanded width, we catch the feedback and send the gripper stop command to stop it where it is.

Returns:True if command was successful, False otherwise.
Return type:bool
exists

Check if a gripper was identified as connected to the robot.

Returns:True if gripper was detected, False otherwise
Return type:bool
grasp(width, force, speed=None, epsilon_inner=0.005, epsilon_outer=0.005, wait_for_result=True, cb=None)[source]

Grasps an object.

An object is considered grasped if the distance \(d\) between the gripper fingers satisfies \((width - epsilon\_inner) < d < (width + epsilon\_outer)\).

Parameters:
  • width (float) – Size of the object to grasp. [m]
  • speed (float) – Closing speed. [m/s]
  • force (float) – Grasping force. [N]
  • epsilon_inner (float) – Maximum tolerated deviation when the actual grasped width is smaller than the commanded grasp width.
  • epsilon_outer (float) – Maximum tolerated deviation when the actual grasped width is wider than the commanded grasp width.
  • cb – Optional callback function to use when the service call is done
Returns:

True if an object has been grasped, false otherwise.

Return type:

bool

home_joints(wait_for_result=False)[source]

Performs homing of the gripper.

After changing the gripper fingers, a homing needs to be done. This is needed to estimate the maximum grasping width.

Parameters:wait_for_result (bool) – if True, this method will block till response is recieved from server
Returns:success
Return type:bool
joint_effort(joint)[source]

Return the requested joint effort.

Parameters:joint (str) – name of a joint
Return type:float
Returns:effort in Nm of individual joint
joint_efforts()[source]

Return all joint efforts.

Return type:dict({str:float})
Returns:unordered dict of joint name Keys to effort (Nm) Values
joint_names()[source]

Return the names of the joints for the specified limb.

Return type:[str]
Returns:ordered list of joint names.
joint_ordered_efforts()[source]

Return all joint efforts.

Return type:[double]
Returns:joint efforts ordered by joint_names.
joint_ordered_positions()[source]

Return all joint positions.

Return type:[double]
Returns:joint positions ordered by joint_names.
joint_ordered_velocities()[source]

Return all joint velocities.

Return type:[double]
Returns:joint velocities ordered by joint_names.
joint_position(joint)[source]

Return the requested joint position.

Parameters:joint (str) – name of a joint
Return type:float
Returns:position individual joint
joint_positions()[source]

Return all joint positions.

Return type:dict({str:float})
Returns:unordered dict of joint name Keys to pos
joint_velocities()[source]

Return all joint velocities.

Return type:dict({str:float})
Returns:unordered dict of joint name Keys to velocity (rad/s) Values
joint_velocity(joint)[source]

Return the requested joint velocity.

Parameters:joint (str) – name of a joint
Return type:float
Returns:velocity in radians/s of individual joint
move_joints(width, speed=None, wait_for_result=True)[source]

Moves the gripper fingers to a specified width.

Parameters:
  • width (float) – Intended opening width. [m]
  • speed (float) – Closing speed. [m/s]
  • wait_for_result (bool) – if True, this method will block till response is recieved from server
Returns:

True if command was successful, False otherwise.

Return type:

bool

open()[source]

Open gripper to max possible width.

Returns:True if command was successful, False otherwise.
Return type:bool
set_velocity(value)[source]

Set default value for gripper joint motions. Used for move and grasp commands.

Parameters:value (float) – speed value [m/s]
stop_action()[source]

Stops a currently running gripper move or grasp.

Returns:True if command was successful, False otherwise.
Return type:bool

RobotEnable

  • Interface class to reset robot when in recoverable error (use enable_robot.py script in scripts/)
class franka_interface.RobotEnable(robot_params=None)[source]

Bases: object

Class RobotEnable - simple control/status wrapper around robot state

enable() - enable all joints disable() - disable all joints reset() - reset all joints, reset all jrcp faults, disable the robot stop() - stop the robot, similar to hitting the e-stop button

Parameters:robot_params (RobotParams) – A RobotParams instance (optional)
disable()[source]

Disable all joints

enable()[source]

Enable all joints

is_enabled()[source]

Return status of robot

Returns:True if enabled, False otherwise
Return type:bool
state()[source]

Returns the last known robot state.

Return type:str
Returns:“Enabled”/”Disabled”

RobotParams

  • Collects and stores all useful information about the robot from the ROS parameter server
class franka_interface.RobotParams[source]

Bases: object

Interface class for essential ROS parameters on the Franka Emika Panda robot.

get_gripper_joint_names()[source]

Return the names of the joints for the gripper from ROS parameter server (/gripper_config/joint_names).

Return type:[str]
Returns:ordered list of joint names
get_joint_limits()[source]

Get joint limits as defined in ROS parameter server (/robot_config/joint_config/joint_velocity_limit)

Returns:Joint limits for each joints
Return type:franka_core_msgs.msg.JointLimits
get_joint_names()[source]

Return the names of the joints for the robot from ROS parameter server (/robot_config/joint_names).

Return type:[str]
Returns:ordered list of joint names from proximal to distal (i.e. shoulder to wrist). joint names for limb
get_neutral_pose()[source]

Get neutral pose joint positions from parameter server (/robot_config/neutral_pose)

Returns:Joint positions of the robot as defined in parameter server.
Return type:[type]
get_robot_name()[source]

Return the name of class of robot from ROS parameter server. (/robot_config/arm_id)

Return type:str
Returns:name of the robot

franka_moveit

PandaMoveGroupInterface

  • Provides interface to control and plan motions using MoveIt in ROS.
  • Simple methods to plan and execute joint trajectories and cartesian path.
  • Provides easy reset and environment definition functionalities (See ExtendedPlanningSceneInterface below).
class franka_moveit.PandaMoveGroupInterface(use_panda_hand_link=False)[source]
arm_group
Getter:The MoveGroupCommander instance of this object. This is an interface to one group of joints. In this case the group is the joints in the Panda arm. This interface can be used to plan and execute motions on the Panda.
Type:moveit_commander.MoveGroupCommander

Note

For available methods for movegroup, refer MoveGroupCommander.

close_gripper(wait=False)[source]

Close gripper. (Using named states defined in urdf.)

Parameters:wait (bool) – if set to True, blocks till execution is complete; defaults to True

Note

If this named state is not found, your ros environment is probably not using the right panda_moveit_config package. Ensure that sourced package is from this repo –> https://github.com/justagist/panda_moveit_config

display_trajectory(plan)[source]

Display planned trajectory in RViz. Rviz should be open and Trajectory display should be listening to the appropriate trajectory topic.

Parameters:plan – the plan to be executed (from plan_joint_path() or plan_cartesian_path())
execute_plan(plan, group='arm', wait=True)[source]

Execute the planned trajectory

Parameters:
  • plan – The plan to be executed (from plan_joint_path() or plan_cartesian_path())
  • group (str) – The name of the move group (default “arm” for robot; use “hand” for gripper group)
  • wait (bool) – if set to True, blocks till execution is complete
go_to_cartesian_pose(pose, ee_link='', wait=True)[source]

Plan and execute a cartesian path to reach a target by avoiding obstacles in the scene. For planning through multiple points, use func:self._arm_group.set_pose_targets.

Parameters:
  • pose (geomentry_msgs.msg.Pose) – The cartesian pose to be reached. (Use franka_moveit.utils.create_pose_msg() for creating pose messages easily)
  • ee_link (str, optional) – name of end-effector link to be used; uses currently set value by default
  • wait (bool) – if set to True, blocks till execution is complete; defaults to True
go_to_joint_positions(positions, wait=True, tolerance=0.005)[source]
Returns:

status of joint motion plan execution

Return type:

bool

Parameters:
  • positions ([double]) – target joint positions (ordered)
  • wait (bool) – if True, function will wait for trajectory execution to complete
  • tolerance (double) – maximum error in final position for each joint to consider task a success
gripper_group
Getter:The MoveGroupCommander instance of this object. This is an interface to one group of joints. In this case the group is the joints in the Panda gripper. This interface can be used to plan and execute motions of the gripper.
Type:moveit_commander.MoveGroupCommander

Note

For available methods for movegroup, refer MoveGroupCommander.

move_to_neutral(wait=True)[source]

Send arm group to neutral pose defined using named state in urdf.

Parameters:wait (bool) – if set to True, blocks till execution is complete
open_gripper(wait=False)[source]

Open gripper. (Using named states defined in urdf)

Parameters:wait (bool) – if set to True, blocks till execution is complete

Note

If this named state is not found, your ros environment is probably not using the right panda_moveit_config package. Ensure that sourced package is from this repo –> https://github.com/justagist/panda_moveit_config.

plan_cartesian_path(poses)[source]

Plan cartesian path using the provided list of poses.

Parameters:poses ([geomentry_msgs.msg.Pose]) – The cartesian poses to be achieved in sequence. (Use franka_moveit.utils.create_pose_msg() for creating pose messages easily)
Returns:the actual RobotTrajectory (can be used for execute_plan()), a fraction of how much of the path was followed
Return type:[RobotTrajectory, float (0,1)]

Note

This method will NOT make the robot avoid obstacles defined in scene. Use func:go_to_cartesian_pose for moving to target pose and avoiding obstacles.

plan_joint_path(joint_position)[source]
Returns:RobotTrajectory plan for executing joint trajectory (can be used for execute_plan())
Parameters:joint_position ([float]*7) – target joint positions
robot_state_interface
Getter:The RobotCommander instance of this object
Type:moveit_commander.RobotCommander

Note

For available methods for RobotCommander, refer RobotCommander.

scene
Getter:The PlanningSceneInterface instance for this robot. This is an interface to the world surrounding the robot
Type:franka_moveit.ExtendedPlanningSceneInterface

Note

For other available methods for planning scene interface, refer PlanningSceneInterface.

set_velocity_scale(value, group='arm')[source]

Set the max velocity scale for executing planned motion.

Parameters:value (float) – scale value (allowed (0,1] )

Helper Functions

franka_moveit.utils.create_pose_msg(position, orientation)[source]

Create Pose message using the provided position and orientation

Returns:

Pose message for the give end-effector position and orientation

Return type:

geometry_msgs.msg.Pose

Parameters:
  • position ([float]*3) – End-effector position in base frame of the robot
  • orientation (quaternion.quaternion (OR) [float] size 4: (w,x,y,z)) – orientation quaternion of end-effector in base frame
franka_moveit.utils.create_pose_stamped_msg(position, orientation, frame='world')[source]

Create PoseStamped message using the provided position and orientation

Returns:

Pose message for the give end-effector position and orientation

Return type:

geometry_msgs.msg.Pose

Parameters:
  • position ([float]*3) – End-effector position in base frame of the robot
  • orientation (quaternion.quaternion (OR) [float] size 4: (w,x,y,z)) – orientation quaternion of end-effector in base frame
  • frame (str) – Name of the parent frame

ExtendedPlanningSceneInterface

  • Easily define scene for robot motion planning (MoveIt plans will avoid defined obstacles if possible).
class franka_moveit.ExtendedPlanningSceneInterface[source]

Bases: moveit_commander.planning_scene_interface.PlanningSceneInterface

Note

For other available methods for planning scene interface, refer PlanningSceneInterface.

add_box(name, pose, size, timeout=5)[source]

Add object to scene and check if it is created.

Parameters:
remove_box(box_name, timeout=5)[source]

Remove box from scene.

Parameters:
  • box_name (str) – name of object
  • timeout (float) – time in sec to wait while checking if box is created

franka_tools

CollisionBehaviourInterface

  • Define collision and contact thresholds for the robot safety and contact detection.
class franka_tools.CollisionBehaviourInterface[source]

Bases: object

Helper class to set collision and contact thresholds at cartesian and joint levels. (This class has no ‘getter’ functions to access the currently set collision behaviour valures.)

set_collision_threshold(joint_torques=None, cartesian_forces=None)[source]
Returns:

True if service call successful, False otherwise

Return type:

bool

Parameters:
  • joint_torques ([float] size 7) – Joint torque threshold for collision (robot motion stops if violated)
  • cartesian_forces ([float] size 6) – Cartesian force threshold for collision detection [x,y,z,R,P,Y] (robot motion stops if violated)
set_contact_threshold(joint_torques=None, cartesian_forces=None)[source]
Returns:

True if service call successful, False otherwise

Return type:

bool

Parameters:
  • joint_torques ([float] size 7) – Joint torque threshold for identifying as contact
  • cartesian_forces ([float] size 6) – Cartesian force threshold for identifying as contact
set_force_threshold_for_collision(cartesian_force_values)[source]
Returns:True if service call successful, False otherwise
Return type:bool
Parameters:cartesian_force_values ([float] size 6) – Cartesian force threshold for collision detection [x,y,z,R,P,Y] (robot motion stops if violated)
set_force_threshold_for_contact(cartesian_force_values)[source]
Returns:True if service call successful, False otherwise
Return type:bool
Parameters:cartesian_force_values ([float] size 6) – Cartesian force threshold for contact detection [x,y,z,R,P,Y]
set_ft_contact_collision_behaviour(torque_lower=None, torque_upper=None, force_lower=None, force_upper=None)[source]
Returns:

True if service call successful, False otherwise

Return type:

bool

Parameters:
  • torque_lower ([float] size 7) – Joint torque threshold for contact detection
  • torque_upper ([float] size 7) – Joint torque threshold for collision (robot motion stops if violated)
  • force_lower ([float] size 6) – Cartesian force threshold for contact detection [x,y,z,R,P,Y]
  • force_upper ([float] size 6) – Cartesian force threshold for collision detection [x,y,z,R,P,Y] (robot motion stops if violated)

FrankaControllerManagerInterface

  • List, start, stop, load available controllers for the robot
  • Get the current controller status (commands, set points, controller gains, etc.)
  • Update controller parameters through ControllerParamConfigClient (see below)
class franka_tools.FrankaControllerManagerInterface(ns='franka_ros_interface', synchronous_pub=False, sim=False)[source]

Bases: object

Parameters:
  • synchronous_pub (bool) –

    designates the JointCommand Publisher as Synchronous if True and Asynchronous if False.

    Synchronous Publishing means that all joint_commands publishing to the robot’s joints will block until the message has been serialized into a buffer and that buffer has been written to the transport of every current Subscriber. This yields predicable and consistent timing of messages being delivered from this Publisher. However, when using this mode, it is possible for a blocking Subscriber to prevent the joint_command functions from exiting. Unless you need exact JointCommand timing, default to Asynchronous Publishing (False).

  • ns (str) – base namespace of interface (‘frank_ros_interface’/’panda_simulator’)
  • sim (bool) – Flag specifying whether the robot is in simulation or not (can be obtained from franka_interface.RobotParams instance)
controller_dict()[source]

Get all controllers as dict

Returns:name of the controller to be stopped
Return type:dict {‘controller_name’: ControllerState}
current_controller
Getter:Returns the name of currently active controller.
Type:str
default_controller
Getter:Returns the name of the default controller for Franka ROS Interface. (specified in robot_config.yaml). Should ideally default to the same as joint_trajectory_controller().
Type:str
effort_joint_position_controller
Getter:Returns the name of effort-based joint position controller (defined in franka_ros_controllers, and specified in robot_config.yaml). Can be used for changing motion controller using FrankaControllerManagerInterface.set_motion_controller().
Type:str
get_controller_config_client(controller_name)[source]
Returns:The parameter configuration client object associated with the specified controller
Return type:ControllerParamConfigClient obj (if None, returns False)
Parameters:controller_name (str) – name of controller whose config client is required
get_controller_state()[source]

Get the status of the current controller, including set points, computed command, controller gains etc. See the ControllerStateInfo class (above) parameters for more info.

get_current_controller_config_client()[source]
Returns:The parameter configuration client object associated with the currently active controller
Return type:ControllerParamConfigClient obj (if None, returns False)
Parameters:controller_name (str) – name of controller whose config client is required
is_loaded(controller_name)[source]

Check if the given controller is loaded.

Parameters:controller_name (str) – name of controller whose status is to be checked
Returns:True if controller is loaded, False otherwise
Return type:bool
is_running(controller_name)[source]

Check if the given controller is running.

Parameters:controller_name (str) – name of controller whose status is to be checked
Returns:True if controller is running, False otherwise
Return type:bool
joint_impedance_controller
Getter:Returns the name of joint impedance controller (defined in franka_ros_controllers, and specified in robot_config.yaml). Can be used for changing motion controller using FrankaControllerManagerInterface.set_motion_controller().
Type:str
joint_position_controller
Getter:Returns the name of joint position controller (defined in franka_ros_controllers, and specified in robot_config.yaml). Can be used for changing motion controller using FrankaControllerManagerInterface.set_motion_controller().
Type:str
joint_torque_controller
Getter:Returns the name of joint torque controller (defined in franka_ros_controllers, and specified in robot_config.yaml). Can be used for changing motion controller using FrankaControllerManagerInterface.set_motion_controller().
Type:str
joint_trajectory_controller
Getter:Returns the name of joint trajectory controller (defined in franka_ros_controllers, and specified in robot_config.yaml). Can be used for changing motion controller using FrankaControllerManagerInterface.set_motion_controller(). This controller exposes trajectory following service.
Type:str
joint_velocity_controller
Getter:Returns the name of joint velocity controller (defined in franka_ros_controllers, and specified in robot_config.yaml). Can be used for changing motion controller using FrankaControllerManagerInterface.set_motion_controller().
Type:str
list_active_controller_names(only_motion_controllers=False)[source]
Returns:List of names active controllers associated to a controller manager namespace.
Return type:[str]
Parameters:only_motion_controller (bool) – if True, only motion controllers are returned
list_active_controllers(only_motion_controllers=False)[source]
Returns:List of active controllers associated to a controller manager namespace. Contains both stopped/running controllers, as returned by the list_controllers service, plus uninitialized controllers with configurations loaded in the parameter server.
Return type:[ControllerState obj]
Parameters:only_motion_controller (bool) – if True, only motion controllers are returned
list_controller_names()[source]
Returns:List of names all controllers associated to a controller manager namespace.
Return type:[str]
Parameters:only_motion_controller (bool) – if True, only motion controllers are returned
list_controller_types()[source]
Returns:List of controller types associated to a controller manager namespace. Contains both stopped/running/loaded controllers, as returned by the list_controller_types service, plus uninitialized controllers with configurations loaded in the parameter server.
Return type:[str]
list_controllers()[source]
Returns:List of controllers associated to a controller manager namespace. Contains both stopped/running controllers, as returned by the list_controllers service, plus uninitialized controllers with configurations loaded in the parameter server.
Return type:[ControllerState obj]
list_loaded_controllers()[source]
Returns:List of controller types associated to a controller manager namespace. Contains all loaded controllers, as returned by the list_controller_types service, plus uninitialized controllers with configurations loaded in the parameter server.
Return type:[str]
list_motion_controllers()[source]
Returns:List of motion controllers associated to a controller manager namespace. Contains both stopped/running controllers, as returned by the list_controllers service, plus uninitialized controllers with configurations loaded in the parameter server.
Return type:[ControllerState obj]
load_controller(name)[source]

Loads the specified controller

Parameters:name (str) – name of the controller to be loaded
set_motion_controller(controller_name)[source]

Set the specified controller as the (only) motion controller

Returns:name of currently active controller (can be used to switch back to this later)
Return type:str
Parameters:controller_name (str) – name of controller to start
start_controller(name)[source]

Starts the specified controller

Parameters:name (str) – name of the controller to be started
stop_controller(name)[source]

Stops the specified controller

Parameters:name (str) – name of the controller to be stopped
unload_controller(name)[source]

Unloads the specified controller

Parameters:name (str) – name of the controller to be unloaded

ControllerParamConfigClient

  • Get and set the controller parameters (gains) for the active controller
class franka_tools.ControllerParamConfigClient(controller_name)[source]

Interface class for updating dynamically configurable paramters of a controller.

Parameters:controller_name (str) – The name of the controller.
get_config(timeout=5)[source]
Returns:the currently set values for all paramters from the server
Return type:dict {str : float}
Parameters:timeout (float) – time to wait before giving up on service request
get_controller_gains(timeout=5)[source]
Returns:the currently set values for controller gains from the server
Return type:( [float], [float] )
Parameters:timeout (float) – time to wait before giving up on service request
get_joint_motion_smoothing_parameter(timeout=5)[source]
Returns:the currently set value for the joint position smoothing parameter from the server.
Return type:float
Parameters:timeout (float) – time to wait before giving up on service request
get_parameter_descriptions(timeout=5)[source]
Returns:the description of each parameter as defined in the cfg file from the server.
Return type:dict {str : str}
Parameters:timeout (float) – time to wait before giving up on service request
is_running
Returns:True if client is running / server is unavailable; False otherwise
Return type:bool
set_controller_gains(k_gains, d_gains=None)[source]

Update the stiffness and damping parameters of the joints for the current controller.

Parameters:
  • k_gains ([float]) – joint stiffness parameters (should be within limits specified in franka documentation; same is also set in franka_ros_controllers/cfg/joint_controller_params.cfg)
  • d_gains ([float]) – joint damping parameters (should be within limits specified in franka documentation; same is also set in franka_ros_controllers/cfg/joint_controller_params.cfg)
set_joint_motion_smoothing_parameter(value)[source]
Update the joint motion smoothing parameter (only valid for
position_joint_position_controller).
Parameters:value ([float]) – smoothing factor (should be within limit set in franka_ros_controllers/cfg/joint_controller_params.cfg)
start(timeout=5)[source]

Start the dynamic_reconfigure client

Parameters:timeout (float) – time to wait before giving up on service request
update_config(**kwargs)[source]

Update the config in the server using the provided keyword arguments.

Parameters:kwargs – These are keyword arguments matching the parameter names in config file: franka_ros_controllers/cfg/joint_controller_params.cfg

FrankaFramesInterface

  • Get and Set end-effector frame and stiffness frame of the robot easily
  • Set the frames to known frames (such as links on the robot) directly
class franka_tools.FrankaFramesInterface[source]

Bases: object

Helper class to retrieve and set EE frames.

Note

The current (realtime) transformation of the end-effector frame and stiffness frame has to be updated externally each time franka states is updated. All of this is done automatically within the ArmInterface class, so use the instance of FrankaFramesInterface from the ArmInterface object using get_frames_interface for ease.

Note

All controllers have to be unloaded before switching frames. This has to be done externally (also automatically handled in ArmInterface class).

Note

It is best to provide all transformation matrices using numpy arrays. If providing as flattened 1D list, make sure it is in column major format.

EE_frame_already_set(frame)[source]
Returns:True if the requested frame is already the current EE frame
Return type:bool
Parameters:frame (np.ndarray (shape: [4,4]), or list (flattened column major 4x4)) – 4x4 transformation matrix representing frame
frames_are_same(frame1, frame2)[source]
Returns:

True if two transformation matrices are equal

Return type:

bool

Parameters:
  • frame1 (np.ndarray (shape: [4,4]), or list (flattened column major 4x4)) – 4x4 transformation matrix representing frame1
  • frame2 (np.ndarray (shape: [4,4]), or list (flattened column major 4x4)) – 4x4 transformation matrix representing frame2
get_EE_frame(as_mat=False)[source]

Get current EE frame transformation matrix in flange frame

Parameters:as_mat (bool) – if True, return np array, else as list
Return type:[float (16,)] / np.ndarray (4x4)
Returns:transformation matrix of EE frame wrt flange frame (column major)
get_K_frame(as_mat=False)[source]

Get current K frame transformation matrix in EE frame

Parameters:as_mat (bool) – if True, return np array, else as list
Return type:[float (16,)] / np.ndarray (4x4)
Returns:transformation matrix of K frame wrt EE frame

Get \(4 imes 4\) transformation matrix of a frame with respect to another. :return: \(4 imes 4\) transformation matrix :rtype: np.ndarray :param frame_name: Name of the child frame from the TF tree :type frame_name: str :param parent: Name of parent frame (default: ‘panda_NE’, the default nominal end-effector frame set in Desk) :type parent: str

reset_EE_frame()[source]

Reset EE frame to default. (defined by DEFAULT_TRANSFORMATIONS.EE_FRAME global variable defined above) By default, this is identity aligning it with the nominal end-effector frame.

Return type:bool
Returns:success status of service request
reset_K_frame()[source]

Reset K frame to default. (defined by DEFAULT_K_FRAME global variable defined above) By default this resets to align the stiffness frame to the end-effector frame.

Return type:bool
Returns:success status of service request
set_EE_at_frame(frame_name, timeout=5.0)[source]

Set new EE frame to the same frame as the link frame given by ‘frame_name’. Only ‘panda_link7’, ‘panda_link8’, ‘panda_hand’, ‘panda_NE’, and ‘panda_EE’ are valid frames for this operation. Other frames will not produce required results. Motion controllers should be stopped for switching.

Parameters:frame_name (str) – desired tf frame name in the tf tree
Return type:[bool, str]
Returns:[success status of service request, error msg if any]
set_EE_frame(frame)[source]

Set new EE frame based on the transformation given by ‘frame’, which is the transformation matrix defining the new desired EE frame with respect to the nominal end-effector frame (NE_T_EE).

Parameters:frame ([float (16,)] / np.ndarray (4x4)) – transformation matrix of new EE frame wrt nominal end-effector frame (if list, should be column major)
Return type:bool
Returns:success status of service request
set_K_at_frame(frame_name, timeout=5.0)[source]

Set new K frame to the same frame as the link frame given by ‘frame_name’ Only ‘panda_link7’, ‘panda_link8’, ‘panda_hand’, ‘panda_NE’, and ‘panda_EE’ are valid frames for this operation. Other frames will not produce required results. Motion controllers should be stopped for switching.

Parameters:frame_name (str) – desired tf frame name in the tf tree
Return type:[bool, str]
Returns:[success status of service request, error msg if any]
set_K_frame(frame)[source]

Set new K frame based on the transformation given by ‘frame’, which is the transformation matrix defining the new desired K frame with respect to the EE frame.

Parameters:frame ([float (16,)] / np.ndarray (4x4)) – transformation matrix of new K frame wrt EE frame
Return type:bool
Returns:success status of service request

JointTrajectoryActionClient

  • Command robot to given joint position(s) smoothly. (Uses the FollowJointTrajectory service from ROS control_msgs package)
  • Smoothly move to a desired (valid) pose without having to interpolate for smoothness (trajectory interpolation done internally)
class franka_tools.JointTrajectoryActionClient(joint_names, controller_name='position_joint_trajectory_controller')[source]

Bases: object

To use this class, the currently active controller for the franka robot should be the “joint_position_trajectory_controller”. This can be set using instance of franka_tools.FrankaControllerManagerInterface.

add_point(positions, time, velocities=None)[source]

Add a waypoint to the trajectory.

Parameters:
  • positions ([float]*7) – target joint positions
  • time (float) – target time in seconds from the start of trajectory to reach the specified goal
  • velocities ([float]*7) – goal velocities for joints (give atleast 0.0001)

Note

Velocities should be greater than zero (done by default) for smooth motion.

clear()[source]

Clear all waypoints from the current trajectory definition.

result()[source]

Get result from trajectory action server

start()[source]

Execute previously defined trajectory.

stop()[source]

Stop currently executing trajectory.

wait(timeout=15.0)[source]

Wait for trajectory execution result.

Parameters:timeout (float) – timeout before cancelling wait