00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include <ros/ros.h>
00038 #include <pr2_controllers_msgs/Pr2GripperCommandAction.h>
00039 #include <actionlib/client/simple_action_client.h>
00040
00041
00042 typedef actionlib::SimpleActionClient<pr2_controllers_msgs::Pr2GripperCommandAction> GripperClient;
00043
00044 class Gripper{
00045 private:
00046 GripperClient* gripper_client_;
00047
00048 public:
00049
00050 Gripper(){
00051
00052
00053
00054 gripper_client_ = new GripperClient("r_gripper_sensor_controller/gripper_action", true);
00055
00056
00057 while(!gripper_client_->waitForServer(ros::Duration(5.0))){
00058 ROS_INFO("Waiting for the r_gripper_sensor_controller/gripper_action action server to come up");
00059 }
00060 }
00061
00062 ~Gripper(){
00063 delete gripper_client_;
00064 }
00065
00066
00067 void open(){
00068 pr2_controllers_msgs::Pr2GripperCommandGoal open;
00069 open.command.position = 0.08;
00070 open.command.max_effort = -1.0;
00071
00072 ROS_INFO("Sending open goal");
00073 gripper_client_->sendGoal(open);
00074 gripper_client_->waitForResult();
00075 if(gripper_client_->getState() == actionlib::SimpleClientGoalState::SUCCEEDED)
00076 ROS_INFO("The gripper opened!");
00077 else
00078 ROS_INFO("The gripper failed to open.");
00079 }
00080
00081
00082 void close(){
00083 pr2_controllers_msgs::Pr2GripperCommandGoal squeeze;
00084 squeeze.command.position = 0.0;
00085 squeeze.command.max_effort = -1.0;
00086
00087 ROS_INFO("Sending squeeze goal");
00088 gripper_client_->sendGoal(squeeze);
00089 gripper_client_->waitForResult();
00090 if(gripper_client_->getState() == actionlib::SimpleClientGoalState::SUCCEEDED)
00091 ROS_INFO("The gripper closed!");
00092 else
00093 ROS_INFO("The gripper failed to close.");
00094 }
00095 };
00096
00097 int main(int argc, char** argv){
00098 ros::init(argc, argv, "simple_gripper");
00099
00100 Gripper gripper;
00101
00102 gripper.open();
00103 gripper.close();
00104
00105 return 0;
00106 }