Go to the documentation of this file.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 <pr2_gripper_sensor_msgs/PR2GripperFindContactAction.h>
00040 #include <pr2_gripper_sensor_msgs/PR2GripperSlipServoAction.h>
00041 #include <actionlib/client/simple_action_client.h>
00042
00043 typedef actionlib::SimpleActionClient<pr2_gripper_sensor_msgs::PR2GripperSlipServoAction> SlipClient;
00044
00045 typedef actionlib::SimpleActionClient<pr2_gripper_sensor_msgs::PR2GripperFindContactAction> ContactClient;
00046
00047 typedef actionlib::SimpleActionClient<pr2_controllers_msgs::Pr2GripperCommandAction> GripperClient;
00048
00049
00050
00051 class Gripper{
00052 private:
00053 GripperClient* gripper_client_;
00054 ContactClient* contact_client_;
00055 SlipClient* slip_client_;
00056
00057 public:
00058
00059 Gripper(){
00060
00061
00062
00063 gripper_client_ = new GripperClient("r_gripper_sensor_controller/gripper_action", true);
00064 contact_client_ = new ContactClient("r_gripper_sensor_controller/find_contact",true);
00065 slip_client_ = new SlipClient("r_gripper_sensor_controller/slip_servo",true);
00066
00067
00068
00069 while(!gripper_client_->waitForServer(ros::Duration(5.0))){
00070 ROS_INFO("Waiting for the r_gripper_sensor_controller/gripper_action action server to come up");
00071 }
00072
00073 while(!contact_client_->waitForServer(ros::Duration(5.0))){
00074 ROS_INFO("Waiting for the r_gripper_sensor_controller/find_contact action server to come up");
00075 }
00076
00077 while(!slip_client_->waitForServer(ros::Duration(5.0))){
00078 ROS_INFO("Waiting for the r_gripper_sensor_controller/slip_servo action server to come up");
00079 }
00080 }
00081
00082 ~Gripper(){
00083 delete gripper_client_;
00084 delete contact_client_;
00085 delete slip_client_;
00086
00087 }
00088
00089
00090 void open(){
00091 pr2_controllers_msgs::Pr2GripperCommandGoal open;
00092 open.command.position = 0.09;
00093
00094 ROS_INFO("Sending open goal");
00095 gripper_client_->sendGoal(open);
00096 gripper_client_->waitForResult();
00097 if(gripper_client_->getState() == actionlib::SimpleClientGoalState::SUCCEEDED)
00098 ROS_INFO("The gripper opened!");
00099 else
00100 ROS_INFO("The gripper failed to open.");
00101 }
00102
00103
00104
00105
00106
00107 void findTwoContacts(){
00108 pr2_gripper_sensor_msgs::PR2GripperFindContactGoal findTwo;
00109 findTwo.command.contact_conditions = findTwo.command.BOTH;
00110 findTwo.command.zero_fingertip_sensors = true;
00111
00112 ROS_INFO("Sending find 2 contact goal");
00113 contact_client_->sendGoal(findTwo);
00114 contact_client_->waitForResult(ros::Duration(5.0));
00115 if(contact_client_->getState() == actionlib::SimpleClientGoalState::SUCCEEDED)
00116 {
00117 ROS_INFO("Contact found. Left: %d, Right: %d", contact_client_->getResult()->data.left_fingertip_pad_contact,
00118 contact_client_->getResult()->data.right_fingertip_pad_contact);
00119 ROS_INFO("Contact force. Left: %f, Right: %f", contact_client_->getResult()->data.left_fingertip_pad_force,
00120 contact_client_->getResult()->data.right_fingertip_pad_force);
00121 }
00122 else
00123 ROS_INFO("The gripper did not find a contact.");
00124 }
00125
00126
00127
00128 void slipServo(){
00129 pr2_gripper_sensor_msgs::PR2GripperSlipServoGoal slip_goal;
00130
00131 ROS_INFO("Slip Servoing");
00132 slip_client_->sendGoal(slip_goal);
00133
00134 if(slip_client_->getState() == actionlib::SimpleClientGoalState::SUCCEEDED)
00135 {}
00136 else
00137 ROS_INFO("The gripper did not find a contact or could not maintain contact force.");
00138 }
00139 };
00140
00141 int main(int argc, char** argv){
00142 ros::init(argc, argv, "simple_gripper");
00143
00144 Gripper gripper;
00145
00146
00147 gripper.open();
00148 sleep(3.0);
00149 gripper.findTwoContacts();
00150 gripper.slipServo();
00151
00152 return 0;
00153 }