Python API Documentation

PandaArm

Note

The generated documentation below also includes relevant methods that are inherited from parent franka_interface.ArmInterface and therefore their definitions and docs might not be found in the source code file of PandaArm; their definitions and docstring sources are in the source files of the parent class. (Inherited methods can be identified by the lack a link for [source] next to their names in the docs below.)

class panda_robot.PandaArm(on_state_callback=None, reset_frames=True)[source]

Methods from franka_interface.ArmInterface are also available to objects of this class.

Bases:

franka_interface.ArmInterface

Parameters:
angles(include_gripper=False)[source]
Returns:current joint positions
Return type:[float]
Parameters:include_gripper (bool) – if True, append gripper joint positions to list
Returns:name of base link frame
Return type:str
cartesian_velocity(joint_angles=None)[source]

Get cartesian end-effector velocity. To get velocity from franka_ros_interface directly, use method ee_velocity().

Returns:end-effector velocity computed using kdl
Return type:numpy.ndarray
Parameters:joint_angles ([float]) – joint angles (optional)
coriolis_comp()

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.
ee_pose()[source]
Returns:end-effector pose as position and quaternion in global frame obtained directly from robot state
Return type:numpy.ndarray (pose), np.quaternion (orientation)
ee_velocity(real_robot=True)[source]
Returns:end effector velocity (linear and angular) computed using finite difference
Return type:numpy.ndarray, numpy.ndarray
Parameters:real_robot (bool) – if False, computes ee velocity using finite difference

If real_robot is False, this is a simple finite difference based velocity computation. Please note that this might produce a bug since some values gets updated only if ee_velocity() is called. [TODO: This can be fixed by moving the update to the state callback method.]

efforts(include_gripper=False)[source]
Returns:current joint efforts (measured torques)
Return type:[float]
Parameters:include_gripper (bool) – if True, append gripper joint efforts to list
enable_robot()[source]

Re-enable robot if stopped due to collision or safety.

Returns:name of end-effector frame
Return type:str
endpoint_effort(in_base_frame=True)

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
error_in_current_state()

Return True if the specified limb has experienced an error.

Return type:bool
Returns:True if the arm has error, False otherwise.
exec_gripper_cmd(pos, force=None)[source]

Move gripper joints to the desired width (space between finger joints), while applying the specified force (optional)

Parameters:
  • pos (float) – desired width [m]
  • force (float) – desired force to be applied on object [N]
Returns:

True if command was successful, False otherwise.

Return type:

bool

exec_position_cmd(cmd)[source]

Execute position control on the robot (raw positions). Be careful while using. Send smooth commands (positions that are very small distance apart from current position).

Parameters:cmd ([float]) – desired joint postions, ordered from joint1 to joint7 (optionally, give desired gripper width as 8th element of list)
exec_position_cmd_delta(cmd)[source]

Execute position control based on desired change in joint positions wrt current joint positions.

Parameters:cmd ([float]) – desired joint postion changes, ordered from joint1 to joint7
exec_torque_cmd(cmd)[source]

Execute torque command at joint level directly

Parameters:cmd ([float]) – desired joint torques, ordered from joint1 to joint7
exec_velocity_cmd(cmd)[source]

Execute velocity command at joint level (using internal velocity controller)

Parameters:cmd ([float]) – desired joint velocities, ordered from joint1 to joint7
exit_control_mode(timeout=5, velocity_tolerance=0.01)

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
forward_kinematics(joint_angles=None, ori_type='quat')[source]
Returns:

position and orientaion of end-effector for the current/provided joint angles

Return type:

[numpy.ndarray, numpy.ndarray (or) quaternion.quaternion]

Parameters:
  • joint_angles ([float]) – joint angles (optional) for which the ee pose is to be computed
  • ori_type (str) – to specify the orientation representation to return (‘quat’,’mat’,’eul’)
get_controller_manager()
Returns:the FrankaControllerManagerInterface instance associated with the robot.
Return type:franka_tools.FrankaControllerManagerInterface
get_flange_pose(pos=None, ori=None)

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()
Returns:the FrankaFramesInterface instance associated with the robot.
Return type:franka_tools.FrankaFramesInterface
get_gripper()[source]
Returns:gripper instance
Return type:franka_interface.GripperInterface
get_joint_limits()

Return the joint limits (defined in the parameter server)

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

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()

Return gravity compensation torques.

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

Return Gripper state {‘position’, ‘force’}. Only available if Franka gripper is connected.

Return type:dict ({str : numpy.ndarray (shape:(2,)), str : numpy.ndarray (shape:(2,))})
Returns:dict of position and force
has_collided()

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

has_gripper
Returns:True if gripper is initialised, else False
Return type:bool
in_safe_state()

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.
inertia(joint_angles=None)[source]
Returns:inertia matrix of robot at current state as computed using KDL (should be close to the value provided by libfranka through franka_interface.ArmInterface.joint_inertia_matrix() when no argument is passed; Exact match may not be available due to dynamics model and computation errors.)
Return type:numpy.ndarray
Parameters:joint_angles ([float]) – joint angles (optional)
inverse_kinematics(pos, ori=None, seed=None, null_space_goal=None, **kwargs)[source]
Returns:

get the joint positions using inverse kinematics from the provided end-effector pose

Return type:

bool (success), [float]

Parameters:
  • pos ([float]) – end-effector position (x,y,z)
  • ori ([float] or np.quaternion) – end-effector orientation (quaternion)
  • seed ([float]) – seed joints to start ik computation
  • null_space_goal ([float]) – null-space joint position if required

kwargs are to avoid breaking of sister classes for arguments that are not used in this class.

jacobian(joint_angles=None)[source]
Returns:jacobian matrix of robot at current state as computed using KDL (should match the value provided by libfranka through franka_interface.ArmInterface.zero_jacobian() when no argument is passed)
Return type:numpy.ndarray
Parameters:joint_angles ([float]) – joint angles (optional) for which the jacobian is to be computed
joint_inertia_matrix()

Returns the current joint inertia matrix given by libfranka.

Returns:joint inertia matrix (7,7)
Return type:np.ndarray [7x7]
joint_limits()[source]
Returns:joint limits
Return type:[{‘lower’: float, ‘upper’: float}]
joint_names()

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).
move_to_cartesian_pose(pos, ori=None, use_moveit=True)

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_pos_delta(cmd)[source]

Execute motion (using moveit; if moveit not available attempts with trajectory controller) based on desired change in joint position wrt to current joint positions

Parameters:cmd ([float]) – desired joint postion changes, ordered from joint1 to joint7
move_to_joint_position(joint_angles, timeout=10.0, threshold=0.00085, test=None, use_moveit=True)[source]

Move to joint position specified (using MoveIt by default; if MoveIt server is not running then attempts with trajectory action client).

Note

This method stops the currently active controller for trajectory tracking (and automatically restarts the controller(s) after execution of trajectory).

Parameters:
  • joint_angles ([float]) – desired joint positions, ordered from joint1 to joint7
  • 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)

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]
n_cmd()[source]
Returns:number of control commands (normally same as number of joints)
Return type:int
n_joints()[source]
Returns:number of joints
Return type:int
q_mean()[source]
Returns:mean of joint limits
Return type:[float]
reset_EE_frame()[source]

Note

This method is not available in simulated environment (when using PandaSimulator).

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 EE with the nominal-end effector frame (F_T_NE) in the flange frame (defined in Desk GUI). Motion controllers are stopped and restarted for switching. Also resets the kinematic chain accordingly for PyKDL IK/FK computations.

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

Note

This method is not available in simulated environment (when using PandaSimulator).

Set new EE frame to the same frame as the link frame given by ‘frame_name’. Motion controllers are stopped and restarted for switching. Also resets the kinematic chain for PyKDL IK/FK computations.

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]

Note

This method is not available in simulated environment (when using PandaSimulator).

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. Also resets the kinematic chain for PyKDL IK/FK computations.

Parameters:frame ([float (len = 16)] (or) numpy.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_arm_speed(speed)[source]

Set joint position speed (only effective for move_to_joint_position(), move_to_joint_pos_delta(), and move_to_cartesian_pose)

Parameters:speed (float) – ratio of maximum joint speed for execution; range = [0.0,1.0]
set_collision_threshold(cartesian_forces=None, joint_torques=None)

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)

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_gripper_speed(speed)[source]

Set velocity for gripper motion

Parameters:speed (float) – speed ratio to set
set_joint_position_speed(speed=0.3)

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_velocities(positions, velocities)

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()
state()[source]
Returns:robot state as a dictionary
Return type:dict {str: obj}
tip_state()[source]
Returns:tip (end-effector frame) state dictionary with keys [‘position’, ‘orientation’, ‘force’, ‘torque’, ‘force_K’, ‘torque_K’, ‘linear_vel’, ‘angular_vel’]. All are numpy.ndarray objects of appropriate dims. ‘force’ and ‘torque’ are in the robot’s base frame, while ‘force_K’ and ‘torque_K’ are in the stiffness frame.
Return type:dict {str: obj}
untuck()[source]

Move to neutral pose (using trajectory controller, or moveit (if moveit is available))

velocities(include_gripper=False)[source]
Returns:current joint velocities
Return type:[float]
Parameters:include_gripper (bool) – if True, append gripper joint velocities to list
what_errors()

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()

Returns the current jacobian matrix given by libfranka.

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