38 #include <pr2_controllers_msgs/Pr2GripperCommandAction.h>
39 #include <pr2_gripper_sensor_msgs/PR2GripperFindContactAction.h>
40 #include <pr2_gripper_sensor_msgs/PR2GripperSlipServoAction.h>
41 #include <pr2_gripper_sensor_msgs/PR2GripperGrabAction.h>
42 #include <pr2_gripper_sensor_msgs/PR2GripperForceServoAction.h>
43 #include <std_srvs/Empty.h>
79 ROS_INFO(
"Waiting for the gripper_action action server to come up");
83 ROS_INFO(
"Waiting for the find_contact action server to come up");
87 ROS_INFO(
"Waiting for the slip_servo action server to come up");
92 ROS_INFO(
"Waiting for the force_servo action server to come up");
105 void open(
double position_open){
107 pr2_controllers_msgs::Pr2GripperCommandGoal
open;
108 open.command.position = position_open;
109 open.command.max_effort = -1.0;
117 ROS_INFO(
"The gripper failed to open.");
124 pr2_gripper_sensor_msgs::PR2GripperForceServoGoal squeeze;
125 squeeze.command.fingertip_force = holdForce;
131 ROS_INFO(
"Stable force was achieved");
133 ROS_INFO(
"Stable force was NOT achieved");
139 pr2_gripper_sensor_msgs::PR2GripperFindContactGoal findTwo;
140 findTwo.command.contact_conditions = findTwo.command.BOTH;
141 findTwo.command.zero_fingertip_sensors =
true;
143 ROS_INFO(
"Sending find 2 contact goal");
154 ROS_INFO(
"The gripper did not find a contact.");
164 pr2_gripper_sensor_msgs::PR2GripperSlipServoGoal slip_goal;
182 pr2_gripper_sensor_msgs::PR2GripperGrabFeedback
feedback_;
183 pr2_gripper_sensor_msgs::PR2GripperGrabResult
result_;
198 void executeCB(
const pr2_gripper_sensor_msgs::PR2GripperGrabGoalConstPtr &goal)
204 double fingertip_force_limit;
205 if(!
nh_.
getParam(
"fingertip_force_limit", fingertip_force_limit))
208 double position_open;
214 bool prempted =
false;
215 double contact_force, servo_force;
242 ROS_INFO(
"Find contact found force: %f",contact_force);
253 servo_force = (contact_force/close_speed)*goal->command.hardness_gain;
254 if(servo_force > fingertip_force_limit && fingertip_force_limit > 0)
255 servo_force = fingertip_force_limit;
271 result_.data.rtstate.realtime_controller_state =
feedback_.data.rtstate.realtime_controller_state;
280 int main(
int argc,
char** argv)