## For instruction on writing tutorials ## http://www.ros.org/wiki/WritingTutorials #################################### ##FILL ME IN #################################### ## for a custom note with links: ## note = [[pr2_gripper_sensor_action/Tutorials/Grab and Release an Object Using pr2_gripper_sensor_action]] ## for the canned note of "This tutorial assumes that you have completed the previous tutorials:" just add the links ## note.0= ## descriptive title for the tutorial ## title = Force Control with the PR2 Gripper ## multi-line description to be displayed in search ## description = This tutorial teaches the user how to use the pr2_gripper_sensor_action package to do force control with the PR2 gripper. ## the next tutorial description (optional) ## next = ## links to next tutorial (optional) ## next.0.link= ## next.1.link= ## what level user is this tutorial for ## level= IntermediateCategory ## keywords = #################################### <> <> === Overview and prerequisites === This tutorial will show you to use the basic [[pr2_gripper_sensor_action]] commands of `find_contact` `force_servo` and `gripper_action` to open the gripper, then quickly find contact with an object, and move into a force control mode to hold the object with a user-specified amount of force. Using any of the [[pr2_gripper_sensor_action]] commands requires three components: * a controller that directly sends commands to the joint motors; * an action node that translates your desired actions to low-level commands for the controller; * the higher level program that sends your commands to the action node. The first two of these components are available in ROS as part of the [[pr2_gripper_sensor_action]], [[pr2_gripper_sensor_controller]], and [[pr2_gripper_sensor_msgs]] packages. In this tutorial, we will show you how to use them by writing the third component, the higher level program. === Building pr2_gripper_sensor_action === You'll need to build pr2_gripper_sensor_action, if you haven't already. {{{ rosdep install pr2_gripper_sensor_action rosmake pr2_gripper_sensor_action }}} After that you can bring up a robot [[WgWiki:/PR2/StartRobot|on the hardware]]. === Package setup === In order to create a ROS node that sends goals to the gripper_sensor_action, the first thing we'll need to do is create a package. To do this we'll use the handy roscreate-pkg command where we want to create the package directory: {{{ roscreate-pkg my_gripper_project roscpp actionlib pr2_gripper_sensor_action }}} After this is done we'll need to roscd to the package we created, since we'll be using it as our workspace. {{{ roscd my_gripper_project }}} === Launching the controller and action nodes === Currently the [[pr2_gripper_sensor_controller]] and [[pr2_gripper_sensor_action]] nodes are not brought up by default when you launch the robot. To write a program that uses these resources you will first need to launch the controller and action nodes for both the left and right gripper by running the following launch script: {{{ roslaunch pr2_gripper_sensor_action pr2_gripper_sensor_actions.launch }}} === Creating the Action Client === Now we will make an action client node that grabs and releases an object. Put the following into '''src/my_gripper_project.cpp''': {{{ #!cplusplus block=simple_gripper #include #include #include #include #include // Our Action interface type, provided as a typedef for convenience typedef actionlib::SimpleActionClient ContactClient; // Our Action interface type, provided as a typedef for convenience typedef actionlib::SimpleActionClient GripperClient; // Our Action interface type, provided as a typedef for convenience typedef actionlib::SimpleActionClient ForceClient; class Gripper{ private: GripperClient* gripper_client_; ContactClient* contact_client_; ForceClient* force_client_; public: //Action client initialization Gripper(){ //Initialize the client for the Action interface to the gripper controller //and tell the action client that we want to spin a thread by default gripper_client_ = new GripperClient("r_gripper_sensor_controller/gripper_action", true); contact_client_ = new ContactClient("r_gripper_sensor_controller/find_contact",true); force_client_ = new ForceClient("r_gripper_sensor_controller/force_servo",true); //wait for the gripper action server to come up while(!gripper_client_->waitForServer(ros::Duration(5.0))){ ROS_INFO("Waiting for the r_gripper_sensor_controller/gripper_action action server to come up"); } while(!contact_client_->waitForServer(ros::Duration(5.0))){ ROS_INFO("Waiting for the r_gripper_sensor_controller/find_contact action server to come up"); } while(!force_client_->waitForServer(ros::Duration(5.0))){ ROS_INFO("Waiting for the r_gripper_sensor_controller/force_servo action server to come up"); } } ~Gripper(){ delete gripper_client_; delete contact_client_; delete force_client_; } //Open the gripper void open(){ pr2_controllers_msgs::Pr2GripperCommandGoal open; open.command.position = 0.08; open.command.max_effort = -1.0; ROS_INFO("Sending open goal"); gripper_client_->sendGoal(open); gripper_client_->waitForResult(); if(gripper_client_->getState() == actionlib::SimpleClientGoalState::SUCCEEDED) ROS_INFO("The gripper opened!"); else ROS_INFO("The gripper failed to open."); } //Hold somethign with a constant force in the gripper void hold( double holdForce){ pr2_gripper_sensor_msgs::PR2GripperForceServoGoal squeeze; squeeze.command.fingertip_force = holdForce; // hold with X N of force ROS_INFO("Sending hold goal"); force_client_->sendGoal(squeeze); force_client_->waitForResult(); if(force_client_->getState() == actionlib::SimpleClientGoalState::SUCCEEDED) ROS_INFO("Stable force was achieved"); else ROS_INFO("Stable force was NOT achieved"); } //Find two contacts and go into force control mode void findTwoContacts(){ pr2_gripper_sensor_msgs::PR2GripperFindContactGoal findTwo; findTwo.command.contact_conditions = findTwo.command.BOTH; // close until both fingers contact findTwo.command.zero_fingertip_sensors = true; // zero fingertip sensor values before moving ROS_INFO("Sending find 2 contact goal"); contact_client_->sendGoal(findTwo); contact_client_->waitForResult(ros::Duration(5.0)); if(contact_client_->getState() == actionlib::SimpleClientGoalState::SUCCEEDED) { ROS_INFO("Contact found. Left: %d, Right: %d", contact_client_->getResult()->data.left_fingertip_pad_contact, contact_client_->getResult()->data.right_fingertip_pad_contact); ROS_INFO("Contact force. Left: %f, Right: %f", contact_client_->getResult()->data.left_fingertip_pad_force, contact_client_->getResult()->data.right_fingertip_pad_force); } else ROS_INFO("The gripper did not find a contact or could not maintain contact force."); } }; int main(int argc, char** argv){ ros::init(argc, argv, "simple_gripper"); Gripper gripper; gripper.open(); sleep(2.0); gripper.findTwoContacts(); gripper.hold(10.0); // hold with 10 N of force return 0; } }}} ==== Building ==== Add the following line to the CMakeLists.txt: {{{ rosbuild_add_executable(my_gripper_project src/my_gripper_project.cpp) }}} and make the binary by typing 'make' in the my_gripper_project directory. ==== Running ==== * Bring up a robot. * Make sure the pr2_gripper_sensor controller and action nodes are launched (see above) * Start the ROS console ([[rxconsole]]) to view any errors that occur. * Run your new node that you created: {{{ rosrun my_gripper_project my_gripper_project }}} The robot should now wait a few seconds, grab an object, wait a few more seconds, and release upon object contact with the environment. ## AUTOGENERATED DO NOT DELETE ## TutorialCategory ## FILL IN THE STACK TUTORIAL CATEGORY HERE