(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Moving the gripper

Description: This tutorial shows you how to move the PR2 gripper using the pr2_gripper_action (an action that runs the gripper controller).

Keywords: moving, move, gripper, pr2, pr2_gripper_action, grasp, grab, open, close

Tutorial Level: BEGINNER

Overview and prerequisites

This tutorial shows how to open and close the gripper of the PR-2.

Commanding the gripper to open and close requires three components:

  • a controller that directly sends commands to the joint motors;
  • an action node that accepts as a command a desired position for the gripper, and converts that to low-level commands for the controller;
  • the higher level program that sends desired positions to the action node.

The first two of these components are available in ROS. In this tutorial, we will show you how to use them by writing the third component, the higher level program.

Before you begin, bring up a robot, either on the hardware or in gazebo.

Building pr2_gripper_action

You'll need to build pr2_gripper_action, if you haven't already.

rosdep install pr2_gripper_action
rosmake pr2_gripper_action

Package setup

In order to create a ROS node that sends goals to the gripper 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 simple_gripper roscpp actionlib pr2_controllers_msgs

After this is done we'll need to roscd to the package we created, since we'll be using it as our workspace.

roscd simple_gripper

The gripper action and trajectory controller

The gripper controller is brought up on robot start-up. In general, a controller can be in one of three states:

  • not loaded
  • loaded, but not running (stopped)
  • running

In general, you can use the pr2_controller_manager to check which controllers are available. After you bring up the robot, use the following command:

rosrun pr2_controller_manager pr2_controller_manager list

In the list that is printed, look for a line starting with r_gripper_controller . If you find:

  • r_gripper_controller (running) : the controller is running; you can skip to the next section of this tutorial

  • r_gripper_controller (stopped) : the controller is loaded, but not running. To start it, use again the pr2_controller_manager :

    rosrun pr2_controller_manager pr2_controller_manager start r_gripper_controller
  • no mention of r_gripper_controller : the controller has not been loaded; this probably means that something went wrong during robot start-up. Abort this tutorial and investigate the cause for that.

Note that this usage of the pr2_controller_manager also applies to other controllers, such as the arm trajectory controller or the torso controller.

The action node

The action node is also brought up automatically on robot start-up. To check for it, you can look at the list of active nodes in the r_gripper_controller namespace:

rosnode list r_gripper_controller

Look for the line /r_gripper_controller/gripper_action_node . If you don't find it, the action node was not brought up at robot start-up. Abort this tutorial and investigate the cause for that.

The action goal

The pr2_gripper_action takes in goal messages of type pr2_controllers_msgs/Pr2GripperCommandGoal, which contains a single field, 'command,' of type pr2_controllers_msgs/Pr2GripperCommand. The command has two float64 fields, 'position' and 'max_effort'. The 'position' field specifies the desired gripper opening (the size of the space between the two fingertips) in meters: closed is 0.0, and fully open is approximately 0.09. The 'max_effort' field places a limit on the amount of effort (force in N) to apply while moving to that position. If 'max_effort' is negative, it is ignored.

Creating the action client

Now we will make an action client node that opens and then closes the gripper while limiting the force applied.

Put the following into src/simple_gripper.cpp:

   1 #include <ros/ros.h>
   2 #include <pr2_controllers_msgs/Pr2GripperCommandAction.h>
   3 #include <actionlib/client/simple_action_client.h>
   4 
   5 // Our Action interface type, provided as a typedef for convenience
   6 typedef actionlib::SimpleActionClient<pr2_controllers_msgs::Pr2GripperCommandAction> GripperClient;
   7 
   8 class Gripper{
   9 private:
  10   GripperClient* gripper_client_;  
  11 
  12 public:
  13   //Action client initialization
  14   Gripper(){
  15 
  16     //Initialize the client for the Action interface to the gripper controller
  17     //and tell the action client that we want to spin a thread by default
  18     gripper_client_ = new GripperClient("r_gripper_controller/gripper_action", true);
  19     
  20     //wait for the gripper action server to come up 
  21     while(!gripper_client_->waitForServer(ros::Duration(5.0))){
  22       ROS_INFO("Waiting for the r_gripper_controller/gripper_action action server to come up");
  23     }
  24   }
  25 
  26   ~Gripper(){
  27     delete gripper_client_;
  28   }
  29 
  30   //Open the gripper
  31   void open(){
  32     pr2_controllers_msgs::Pr2GripperCommandGoal open;
  33     open.command.position = 0.08;
  34     open.command.max_effort = -1.0;  // Do not limit effort (negative)
  35     
  36     ROS_INFO("Sending open goal");
  37     gripper_client_->sendGoal(open);
  38     gripper_client_->waitForResult();
  39     if(gripper_client_->getState() == actionlib::SimpleClientGoalState::SUCCEEDED)
  40       ROS_INFO("The gripper opened!");
  41     else
  42       ROS_INFO("The gripper failed to open.");
  43   }
  44 
  45   //Close the gripper
  46   void close(){
  47     pr2_controllers_msgs::Pr2GripperCommandGoal squeeze;
  48     squeeze.command.position = 0.0;
  49     squeeze.command.max_effort = 50.0;  // Close gently
  50     
  51     ROS_INFO("Sending squeeze goal");
  52     gripper_client_->sendGoal(squeeze);
  53     gripper_client_->waitForResult();
  54     if(gripper_client_->getState() == actionlib::SimpleClientGoalState::SUCCEEDED)
  55       ROS_INFO("The gripper closed!");
  56     else
  57       ROS_INFO("The gripper failed to close.");
  58   }
  59 };
  60 
  61 int main(int argc, char** argv){
  62   ros::init(argc, argv, "simple_gripper");
  63 
  64   Gripper gripper;
  65 
  66   gripper.open();
  67   gripper.close();
  68 
  69   return 0;
  70 }

Now we'll go through a few subsets of the code in more detail.

  16     //Initialize the client for the Action interface to the gripper controller
  17     //and tell the action client that we want to spin a thread by default
  18     gripper_client_ = new GripperClient("r_gripper_controller/gripper_action", true);
  19     
  20     //wait for the gripper action server to come up 
  21     while(!gripper_client_->waitForServer(ros::Duration(5.0))){
  22       ROS_INFO("Waiting for the r_gripper_controller/gripper_action action server to come up");
  23     }

Here we initialize the action client and wait for the action server to come up. If the gripper controller has not been started, the action server will not be up.

The message namespace for the gripper action, which we use to initialize the action client, is "r_gripper_controller/gripper_action." If you type

rostopic list

on the command line, you should see an entire set of messages that start with "r_gripper_controller/gripper_action": cancel, feedback, goal, result, and status. We will show how to send action goals in this tutorial; if you type

rostopic echo /r_gripper_controller/gripper_action/feedback

at the command line, you can see the feedback from the action while it executes our command.

  32     pr2_controllers_msgs::Pr2GripperCommandGoal open;
  33     open.command.position = 0.08;
  34     open.command.max_effort = -1.0;  // Do not limit effort (negative)
  35 

  47     pr2_controllers_msgs::Pr2GripperCommandGoal squeeze;
  48     squeeze.command.position = 0.0;
  49     squeeze.command.max_effort = 50.0;  // Close gently
  50 

Gripper action goal messages for opening and closing.

  51     ROS_INFO("Sending squeeze goal");
  52     gripper_client_->sendGoal(squeeze);
  53     gripper_client_->waitForResult();
  54     if(gripper_client_->getState() == actionlib::SimpleClientGoalState::SUCCEEDED)
  55       ROS_INFO("The gripper closed!");
  56     else
  57       ROS_INFO("The gripper failed to close.");

Here we send the goal that closes the gripper, and wait for the action to report that it has terminated. Upon termination, if it reports that it SUCCEEDED, it means that it reached the desired position; if the gripper stalls (for instance, upon hitting an object that prevents it from closing all the way), it will report ABORTED. Because the gripper controller is still running even after the action goal has terminated, the gripper will continue to try to reach the desired position, with the specified maximum effort. This continues until a new goal is sent, or until the gripper controller is stopped. Thus, if the gripper has been commanded to close around an object, it will continue to exert force on the object, holding it in the hand, until told to do otherwise.

Building

Add the following line to the CMakeLists.txt:

rosbuild_add_executable(simple_gripper src/simple_gripper.cpp)

and make the binary by typing 'make' in the simple_gripper directory.

Running

  • Bring up gazebo or a robot.
  • Start the ROS console (rxconsole) to view any errors that occur.

  • Run the controller/action launch file:

roslaunch run_simple_gripper.launch
  • Run the simple_gripper program:

bin/simple_gripper

You should see the robot's right gripper open and close.

Wiki: pr2_controllers/Tutorials/Moving the gripper (last edited 2020-07-20 12:52:47 by RobertZickler)