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> 68 gripper_client_ =
new GripperClient(
"r_gripper_sensor_controller/gripper_action",
true);
69 contact_client_ =
new ContactClient(
"r_gripper_sensor_controller/find_contact",
true);
70 slip_client_ =
new SlipClient(
"r_gripper_sensor_controller/slip_servo",
true);
71 event_detector_client_ =
new EventDetectorClient(
"r_gripper_sensor_controller/event_detector",
true);
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");
127 ROS_INFO(
"Contact found. Left: %d, Right: %d", contact_client_->
getResult()->data.left_fingertip_pad_contact,
128 contact_client_->
getResult()->data.right_fingertip_pad_contact);
129 ROS_INFO(
"Contact force. Left: %f, Right: %f", contact_client_->
getResult()->data.left_fingertip_pad_force,
130 contact_client_->
getResult()->data.right_fingertip_pad_force);
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...");
159 event_detector_client_->
sendGoal(place_goal);
164 ROS_INFO(
"cond met: %d, acc_met: %d, slip_met: %d", event_detector_client_->
getResult()->data.trigger_conditions_met, event_detector_client_->
getResult()->data.acceleration_event, event_detector_client_->
getResult()->data.slip_event);
171 int main(
int argc,
char** argv){
bool waitForServer(const ros::Duration &timeout=ros::Duration(0, 0)) const
bool waitForResult(const ros::Duration &timeout=ros::Duration(0, 0))
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
actionlib::SimpleActionClient< pr2_gripper_sensor_msgs::PR2GripperEventDetectorAction > EventDetectorClient
actionlib::SimpleActionClient< pr2_gripper_sensor_msgs::PR2GripperFindContactAction > ContactClient
ContactClient * contact_client_
int main(int argc, char **argv)
actionlib::SimpleActionClient< pr2_gripper_sensor_msgs::PR2GripperSlipServoAction > SlipClient
void sendGoal(const Goal &goal, SimpleDoneCallback done_cb=SimpleDoneCallback(), SimpleActiveCallback active_cb=SimpleActiveCallback(), SimpleFeedbackCallback feedback_cb=SimpleFeedbackCallback())
GripperClient * gripper_client_
actionlib::SimpleActionClient< pr2_controllers_msgs::Pr2GripperCommandAction > GripperClient
SlipClient * slip_client_
SimpleClientGoalState getState() const
ResultConstPtr getResult() const
EventDetectorClient * event_detector_client_