placeActionTest.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2009, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  *
29  * \author Joe Romano
30  */
31 
32 // @author: Joe Romano
33 // @email: joeromano@gmail.com
34 // @brief: placeActionTest.cpp - example for using the place
35 // action server
36 
37 #include <ros/ros.h>
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>
43 
45 // Our Action interface type, provided as a typedef for convenience
47 // Our Action interface type, provided as a typedef for convenience
49 // Our Action interface type, provided as a typedef for convenience
51 // Our Action interface type, provided as a typedef for convenience
52 
53 
54 
55 class Gripper{
56 private:
61 
62 public:
63  //Action client initialization
65 
66  //Initialize the client for the Action interface to the gripper controller
67  //and tell the action client that we want to spin a thread by default
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);
72 
73 
74  //wait for the gripper action server to come up
75  while(!gripper_client_->waitForServer(ros::Duration(5.0))){
76  ROS_INFO("Waiting for the r_gripper_sensor_controller/gripper_action action server to come up");
77  }
78 
79  while(!contact_client_->waitForServer(ros::Duration(5.0))){
80  ROS_INFO("Waiting for the r_gripper_sensor_controller/find_contact action server to come up");
81  }
82 
83  while(!slip_client_->waitForServer(ros::Duration(5.0))){
84  ROS_INFO("Waiting for the r_gripper_sensor_controller/slip_servo action server to come up");
85  }
86 
87  while(!event_detector_client_->waitForServer(ros::Duration(5.0))){
88  ROS_INFO("Waiting for the r_gripper_sensor_controller/event_detector action server to come up");
89  }
90  }
91 
93  delete gripper_client_;
94  delete contact_client_;
95  delete slip_client_;
97 
98  }
99 
100  //Open the gripper
101  void open(){
102  pr2_controllers_msgs::Pr2GripperCommandGoal open;
103  open.command.position = 0.09; // position open (9 cm)
104  open.command.max_effort = -1.0; // unlimited motor effort
105 
106  ROS_INFO("Sending open goal");
107  gripper_client_->sendGoal(open);
108  gripper_client_->waitForResult();
109  if(gripper_client_->getState() == actionlib::SimpleClientGoalState::SUCCEEDED)
110  ROS_INFO("The gripper opened!");
111  else
112  ROS_INFO("The gripper failed to open.");
113  }
114 
115 
116  //Find two contacts and go into force control mode
118  pr2_gripper_sensor_msgs::PR2GripperFindContactGoal findTwo;
119  findTwo.command.contact_conditions = findTwo.command.BOTH; // close until both fingers contact
120  findTwo.command.zero_fingertip_sensors = true; // zero fingertip sensor values before moving
121 
122  ROS_INFO("Sending find 2 contact goal");
123  contact_client_->sendGoal(findTwo);
124  contact_client_->waitForResult(ros::Duration(5.0));
125  if(contact_client_->getState() == actionlib::SimpleClientGoalState::SUCCEEDED)
126  {
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);
131  }
132  else
133  ROS_INFO("The gripper did not find a contact.");
134  }
135 
136 
137  //Slip servo the robot
138  void slipServo(){
139  pr2_gripper_sensor_msgs::PR2GripperSlipServoGoal slip_goal;
140 
141  ROS_INFO("Slip Servoing");
142  slip_client_->sendGoal(slip_goal);
143  //slip_client_->waitForResult(); // thre is no reason to wait since this action never returns a result
145  ROS_INFO("You Should Never See This Message!");
146  else
147  ROS_INFO("SlipServo Action returned without success.");
148  }
149 
150 
151  //move into event_detector mode to drop an object
152  void place(){
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; // set the contact acceleration to n m/s^2
156  place_goal.command.slip_trigger_magnitude = .005;
157 
158  ROS_INFO("Waiting for object placement contact...");
159  event_detector_client_->sendGoal(place_goal);
160  event_detector_client_->waitForResult();
161  if(event_detector_client_->getState() == actionlib::SimpleClientGoalState::SUCCEEDED)
162  {
163  ROS_INFO("Place Success");
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);
165  }
166  else
167  ROS_INFO("Place Failure");
168  }
169 };
170 
171 int main(int argc, char** argv){
172  ros::init(argc, argv, "simple_gripper");
173 
174  Gripper gripper;
175 
176  // do this until we get ctrl-c
177  // open the hand to prepare for a grasp
178  gripper.open();
179 
180  // wait (you don't have to do this in your code)
181  // in this demo here is a good time to put an object inside the gripper
182  // in your code the robot would move its arm around an object
183  sleep(7.0);
184 
185  // close the gripper until we have a contact on each finger and move into force control mode
186  gripper.findTwoContacts();
187 
188  // now hold the object but don't drop it
189  gripper.slipServo();
190 
191  // now we wait some amount of time until we want to put it down
192  // in your code you probably wouldn't do this but you would move the arm around instead
193  sleep(8.0);
194 
195  // now we decided we are ready to put the object down, so tell the gripper that
196  gripper.place();
197 
198  // open the gripper once placement has been detected
199  gripper.open();
200 
201  return 0;
202 }
bool waitForServer(const ros::Duration &timeout=ros::Duration(0, 0)) const
void findTwoContacts()
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
#define ROS_INFO(...)
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())
void slipServo()
GripperClient * gripper_client_
actionlib::SimpleActionClient< pr2_controllers_msgs::Pr2GripperCommandAction > GripperClient
SlipClient * slip_client_
SimpleClientGoalState getState() const
ResultConstPtr getResult() const
EventDetectorClient * event_detector_client_


pr2_gripper_sensor_action
Author(s): Joe Romano
autogenerated on Wed Apr 1 2020 03:58:26