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/PR2GripperEventDetectorAction.h>
76 ROS_INFO(
"Waiting for the r_gripper_sensor_controller/gripper_action action server to come up");
80 ROS_INFO(
"Waiting for the r_gripper_sensor_controller/find_contact action server to come up");
84 ROS_INFO(
"Waiting for the r_gripper_sensor_controller/slip_servo action server to come up");
88 ROS_INFO(
"Waiting for the r_gripper_sensor_controller/event_detector action server to come up");
102 pr2_controllers_msgs::Pr2GripperCommandGoal
open;
103 open.command.position = 0.09;
104 open.command.max_effort = -1.0;
112 ROS_INFO(
"The gripper failed to open.");
118 pr2_gripper_sensor_msgs::PR2GripperFindContactGoal findTwo;
119 findTwo.command.contact_conditions = findTwo.command.BOTH;
120 findTwo.command.zero_fingertip_sensors =
true;
122 ROS_INFO(
"Sending find 2 contact goal");
133 ROS_INFO(
"The gripper did not find a contact.");
139 pr2_gripper_sensor_msgs::PR2GripperSlipServoGoal slip_goal;
145 ROS_INFO(
"You Should Never See This Message!");
147 ROS_INFO(
"SlipServo Action returned without success.");
153 pr2_gripper_sensor_msgs::PR2GripperEventDetectorGoal place_goal;
154 place_goal.command.trigger_conditions = place_goal.command.FINGER_SIDE_IMPACT_OR_SLIP_OR_ACC;
155 place_goal.command.acceleration_trigger_magnitude = 4.0;
156 place_goal.command.slip_trigger_magnitude = .005;
158 ROS_INFO(
"Waiting for object placement contact...");
171 int main(
int argc,
char** argv){