A Python interface package built over the Franka ROS Interface package, combining its different classes to provide a unified interface for controlling and handling the Franka Emika Panda robot. Also works directly with Panda Simulator.
The package provides an extensive and unified API for controlling and managing the Franka Emika Robot (and gripper) using pre-defined low-level controllers (position, velocity, torque, joint impedance), MoveIt planners, and JointTrajectory action service.
NOTE: This version requires Franka ROS Interface v0.7.1. For usage with older versions, use Panda Robot branch v0.6.0 from Github.
- Provides simple-intuitive interface classes with methods to directly and easily control the robot using low-level controllers, MoveIt planners, or Trajectory action client.
- Get real-time robot state, joint state, controller state, kinematics, dynamics, etc.
- Provides Kinematics computation (using KDL library). Automatically adjusts computations for the end-effector frames set in Dash or by code.
- Integrated with gripper control.
- Manage frames transformation and controller switching using simple utility functions.
- Works directly on simulated robot when using Panda Simulator providing direct sim-to-real and real-to-sim code transfer.
DOCUMENTATION: https://justagist.github.io/panda_robot/
Watch video here
Watch video here
- Franka ROS Interface package. This package should be installed from source (v0.7.1 or master branch) following all instructions in the Installation section.
Clone package to src
folder of your catkin workspace. In catkin root run:
catkin build
source devel/setup.bash
Note: The franka_ros_interface 'driver' should be running in the 'master' environment in one terminal (See Franka ROS Interface instructions for details). Then, any code which uses PandaRobot or Franka ROS Interface should be run in 'master' or 'remote' environment (as appropriate).
Example: Testing interface in terminal
>> python # start interactive python session; make sure the correct ros workspace is sourced.
>> import rospy
>> from panda_robot import PandaArm
>> rospy.init_node("panda_demo") # initialise ros node
>> r = PandaArm() # create PandaArm instance
>> r.move_to_neutral() # moves robot to neutral pose; uses moveit if available, else JointTrajectory action client
>> pos,ori = r.ee_pose() # get current end-effector pose (3d position and orientation quaternion of end-effector frame in base frame)
>> r.get_gripper().home_joints() # homes gripper joints
>> r.get_gripper().open() # open gripper
>> r.move_to_joint_position([-8.48556818e-02, -8.88127666e-02, -6.59622769e-01, -1.57569726e+00, -4.82374882e-04, 2.15975946e+00, 4.36766917e-01]) # move robot to the specified pose
>> r.move_to_cartesian_pose(pos,ori) # move the robot end-effector to pose specified by 'pos','ori'
See script (scripts/controller_test.py
) to see how the robot can be controlled using low-level joint controllers.
See script (scripts/env.py
), and run it interactively (python -i env.py
) for testing other available functionalities. Other available functionalities: https://justagist.github.io/panda_robot/
Copyright (c) 2019-2021, Saif Sidhik