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_gripper_sensor_msgs/PR2GripperGrabAction.h>
00039 #include <pr2_gripper_sensor_msgs/PR2GripperReleaseAction.h>
00040 #include <actionlib/client/simple_action_client.h>
00041
00042
00043 typedef actionlib::SimpleActionClient<pr2_gripper_sensor_msgs::PR2GripperGrabAction> GrabClient;
00044
00045 typedef actionlib::SimpleActionClient<pr2_gripper_sensor_msgs::PR2GripperReleaseAction> ReleaseClient;
00046
00047
00048 class Gripper{
00049 private:
00050 GrabClient* grab_client_;
00051 ReleaseClient* release_client_;
00052
00053 public:
00054
00055 Gripper(){
00056
00057
00058
00059 grab_client_ = new GrabClient("r_gripper_sensor_controller/grab",true);
00060 release_client_ = new ReleaseClient("r_gripper_sensor_controller/release",true);
00061
00062 while(!grab_client_->waitForServer(ros::Duration(5.0))){
00063 ROS_INFO("Waiting for the r_gripper_sensor_controller/grab action server to come up");
00064 }
00065
00066 while(!release_client_->waitForServer(ros::Duration(5.0))){
00067 ROS_INFO("Waiting for the r_gripper_sensor_controller/release action server to come up");
00068 }
00069 }
00070
00071 ~Gripper(){
00072 delete grab_client_;
00073 delete release_client_;
00074 }
00075
00076
00077 void grab(){
00078 pr2_gripper_sensor_msgs::PR2GripperGrabGoal grip;
00079 grip.command.hardness_gain = 0.03;
00080
00081 ROS_INFO("Sending grab goal");
00082 grab_client_->sendGoal(grip);
00083 grab_client_->waitForResult(ros::Duration(20.0));
00084 if(grab_client_->getState() == actionlib::SimpleClientGoalState::SUCCEEDED)
00085 ROS_INFO("Successfully completed Grab");
00086 else
00087 ROS_INFO("Grab Failed");
00088 }
00089
00090 void release(){
00091 pr2_gripper_sensor_msgs::PR2GripperReleaseGoal place;
00092
00093 place.command.event.trigger_conditions = place.command.event.FINGER_SIDE_IMPACT_OR_SLIP_OR_ACC;
00094
00095 place.command.event.acceleration_trigger_magnitude = 5.0;
00096
00097 place.command.event.slip_trigger_magnitude = .01;
00098
00099
00100 ROS_INFO("Waiting for object placement contact...");
00101 release_client_->sendGoal(place);
00102 release_client_->waitForResult();
00103 if(release_client_->getState() == actionlib::SimpleClientGoalState::SUCCEEDED)
00104 ROS_INFO("Release Success");
00105 else
00106 ROS_INFO("Place Failure");
00107
00108 }
00109
00110
00111 };
00112
00113 int main(int argc, char** argv){
00114 ros::init(argc, argv, "simple_gripper");
00115
00116 Gripper gripper;
00117
00118
00119 sleep(5.0);
00120
00121
00122 gripper.grab();
00123
00124
00125 sleep(5.0);
00126
00127
00128 gripper.release();
00129
00130
00131 return 0;
00132 }