38 #include <pr2_controllers_msgs/Pr2GripperCommandAction.h>
39 #include <pr2_gripper_sensor_msgs/PR2GripperFindContactAction.h>
64 ROS_INFO(
"Waiting for the r_gripper_sensor_controller/gripper_action action server to come up");
68 ROS_INFO(
"Waiting for the r_gripper_sensor_controller/find_contact action server to come up");
79 pr2_controllers_msgs::Pr2GripperCommandGoal
open;
80 open.command.position = 0.08;
81 open.command.max_effort = -1.0;
89 ROS_INFO(
"The gripper failed to open.");
94 pr2_gripper_sensor_msgs::PR2GripperFindContactGoal findOne;
95 findOne.command.contact_conditions = findOne.command.EITHER;
96 findOne.command.zero_fingertip_sensors =
true;
99 ROS_INFO(
"Sending find 1 contact goal");
110 ROS_INFO(
"The gripper did not find a contact.");
117 pr2_gripper_sensor_msgs::PR2GripperFindContactGoal findTwo;
118 findTwo.command.contact_conditions = findTwo.command.BOTH;
119 findTwo.command.zero_fingertip_sensors =
true;
122 ROS_INFO(
"Sending find 2 contact goal");
133 ROS_INFO(
"The gripper did not find a contact or could not maintain contact force.");
137 int main(
int argc,
char** argv){