pr2_gripper_grab_action.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: pr2_gripper_grab_action.cpp - action server for the
35 // pr2_gripper_grab action command
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/PR2GripperGrabAction.h>
42 #include <pr2_gripper_sensor_msgs/PR2GripperForceServoAction.h>
43 #include <std_srvs/Empty.h>
46 
47 
49 // Our Action interface type, provided as a typedef for convenience
51 // Our Action interface type, provided as a typedef for convenience
53 // Our Action interface type, provided as a typedef for convenience
55 
56 
57 class Gripper{
58 private:
63 
64 
65 public:
66  //Action client initialization
68 
69  //Initialize the client for the Action interface to the gripper controller
70  //and tell the action client that we want to spin a thread by default
71  gripper_client_ = new GripperClient("gripper_action", true);
72  contact_client_ = new ContactClient("find_contact",true);
73  slip_client_ = new SlipClient("slip_servo",true);
74  force_client_ = new ForceClient("force_servo",true);
75 
76 
77  //wait for the gripper action server to come up
79  ROS_INFO("Waiting for the gripper_action action server to come up");
80  }
81 
83  ROS_INFO("Waiting for the find_contact action server to come up");
84  }
85 
87  ROS_INFO("Waiting for the slip_servo action server to come up");
88  }
89 
90 
92  ROS_INFO("Waiting for the force_servo action server to come up");
93  }
94 
95  }
96 
98  delete gripper_client_;
99  delete contact_client_;
100  delete slip_client_;
101  delete force_client_;
102  }
103 
104  //Open the gripper
105  void open(double position_open){
106 
107  pr2_controllers_msgs::Pr2GripperCommandGoal open;
108  open.command.position = position_open; // position open (9 cm)
109  open.command.max_effort = -1.0;
110 
111  ROS_INFO("Sending open goal");
115  ROS_INFO("The gripper opened!");
116  else
117  ROS_INFO("The gripper failed to open.");
118  }
119 
120 
121 
122  //Hold somethign with a constant force in the gripper
123  int hold( double holdForce){
124  pr2_gripper_sensor_msgs::PR2GripperForceServoGoal squeeze;
125  squeeze.command.fingertip_force = holdForce; // hold with X N of force
126 
127  ROS_INFO("Sending hold goal");
128  force_client_->sendGoal(squeeze);
131  ROS_INFO("Stable force was achieved");
132  else
133  ROS_INFO("Stable force was NOT achieved");
134  return force_client_->getResult()->data.rtstate.realtime_controller_state;
135  }
136 
137  //Find two contacts and go into force control mode
138  int findTwoContacts(double *contact_force){
139  pr2_gripper_sensor_msgs::PR2GripperFindContactGoal findTwo;
140  findTwo.command.contact_conditions = findTwo.command.BOTH; // close until both fingers contact
141  findTwo.command.zero_fingertip_sensors = true; // zero fingertip sensor values before moving
142 
143  ROS_INFO("Sending find 2 contact goal");
144  contact_client_->sendGoal(findTwo);
147  {
148  ROS_INFO("Contact found. Left: %d, Right: %d", contact_client_->getResult()->data.left_fingertip_pad_contact,
149  contact_client_->getResult()->data.right_fingertip_pad_contact);
150  ROS_INFO("Contact force. Left: %f, Right: %f", contact_client_->getResult()->data.left_fingertip_pad_force,
151  contact_client_->getResult()->data.right_fingertip_pad_force);
152  }
153  else
154  ROS_INFO("The gripper did not find a contact.");
155  *contact_force = (contact_client_->getResult()->data.right_fingertip_pad_force + contact_client_->getResult()->data.left_fingertip_pad_force)/2.0;
156 
157  return contact_client_->getResult()->data.rtstate.realtime_controller_state;
158 
159  }
160 
161 
162  //Slip servo the robot
163  void slipServo(){
164  pr2_gripper_sensor_msgs::PR2GripperSlipServoGoal slip_goal;
165 
166  ROS_INFO("Slip Servoing");
167  slip_client_->sendGoal(slip_goal);
168  }
169 
170 };
171 
172 
173 
175 {
176 protected:
177 
180  std::string action_name_;
181  // create messages that are used to published feedback/result
182  pr2_gripper_sensor_msgs::PR2GripperGrabFeedback feedback_;
183  pr2_gripper_sensor_msgs::PR2GripperGrabResult result_;
185 
186 public:
187 
188  PR2GripperGrabAction(std::string name) :
189  as_(nh_, name, boost::bind(&PR2GripperGrabAction::executeCB, this, boost::placeholders::_1)),
190  action_name_(name)
191  {
192  }
193 
195  {
196  }
197 
198  void executeCB(const pr2_gripper_sensor_msgs::PR2GripperGrabGoalConstPtr &goal)
199  {
200  double close_speed;
201  if(!nh_.getParam("close_speed", close_speed))
202  ROS_ERROR("No close_speed given in namespace: '%s')", nh_.getNamespace().c_str());
203 
204  double fingertip_force_limit;
205  if(!nh_.getParam("fingertip_force_limit", fingertip_force_limit))
206  ROS_ERROR("No fingertip_force_limit given in namespace: '%s')", nh_.getNamespace().c_str());
207 
208  double position_open;
209  if(!nh_.getParam("position_open", position_open))
210  ROS_ERROR("No position_open given in namespace: '%s')", nh_.getNamespace().c_str());
211 
212 
213  // helper variables
214  bool prempted = false;
215  double contact_force, servo_force;
216 
217  // check that preempt has not been requested by the client
218  if (as_.isPreemptRequested() || !ros::ok())
219  {
220  ROS_INFO("%s: Preempted", action_name_.c_str());
221  // set the action state to preempted
222  as_.setPreempted();
223  prempted = true;
224  }
225  if(!prempted)
226  gripper.open(position_open);
227 
228  // check that preempt has not been requested by the client
229  if (as_.isPreemptRequested() || !ros::ok())
230  {
231  ROS_INFO("%s: Preempted", action_name_.c_str());
232  // set the action state to preempted
233  as_.setPreempted();
234  prempted = true;
235  }
236  if(!prempted)
237  {
238  feedback_.data.rtstate.realtime_controller_state = gripper.findTwoContacts(&contact_force);
240  }
241 
242  ROS_INFO("Find contact found force: %f",contact_force);
243  // check that preempt has not been requested by the client
244  if (as_.isPreemptRequested() || !ros::ok())
245  {
246  ROS_INFO("%s: Preempted", action_name_.c_str());
247  // set the action state to preempted
248  as_.setPreempted();
249  prempted = true;
250  }
251  if(!prempted)
252  {
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;
256  feedback_.data.rtstate.realtime_controller_state = gripper.hold(servo_force);
258  }
259 
260  // check that preempt has not been requested by the client
261  if (as_.isPreemptRequested() || !ros::ok())
262  {
263  ROS_INFO("%s: Preempted", action_name_.c_str());
264  // set the action state to preempted
265  as_.setPreempted();
266  prempted = true;
267  }
268  if(!prempted)
269  gripper.slipServo();
270 
271  result_.data.rtstate.realtime_controller_state = feedback_.data.rtstate.realtime_controller_state;
272  ROS_INFO("%s: Succeeded", action_name_.c_str());
273  // set the action state to succeeded
274  if(!prempted)
276  }
277 };
278 
279 
280 int main(int argc, char** argv)
281 {
282  ros::init(argc, argv, "grab");
283 
284  PR2GripperGrabAction Grab("grab");
285  ros::spin();
286 
287  return 0;
288 }
289 
Gripper::hold
void hold(double holdForce)
Definition: forceServoActionTest.cpp:120
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
ros.h
Gripper::slipServo
void slipServo()
Definition: pr2_gripper_grab_action.cpp:163
actionlib::SimpleActionClient::waitForServer
bool waitForServer(const ros::Duration &timeout=ros::Duration(0, 0)) const
PR2GripperGrabAction::~PR2GripperGrabAction
~PR2GripperGrabAction(void)
Definition: pr2_gripper_grab_action.cpp:194
SlipClient
actionlib::SimpleActionClient< pr2_gripper_sensor_msgs::PR2GripperSlipServoAction > SlipClient
Definition: pr2_gripper_grab_action.cpp:48
simple_action_server.h
boost
PR2GripperGrabAction::nh_
ros::NodeHandle nh_
Definition: pr2_gripper_grab_action.cpp:178
Gripper::Gripper
Gripper()
Definition: pr2_gripper_grab_action.cpp:67
actionlib::SimpleActionServer::isPreemptRequested
bool isPreemptRequested()
Gripper::slip_client_
SlipClient * slip_client_
Definition: placeActionTest.cpp:59
Gripper::findTwoContacts
void findTwoContacts()
Definition: findContactActionTest.cpp:116
PR2GripperGrabAction::feedback_
pr2_gripper_sensor_msgs::PR2GripperGrabFeedback feedback_
Definition: pr2_gripper_grab_action.cpp:182
actionlib::SimpleActionServer::publishFeedback
void publishFeedback(const Feedback &feedback)
actionlib::SimpleActionServer::setSucceeded
void setSucceeded(const Result &result=Result(), const std::string &text=std::string(""))
ros::ok
ROSCPP_DECL bool ok()
Gripper::findTwoContacts
int findTwoContacts(double *contact_force)
Definition: pr2_gripper_grab_action.cpp:138
PR2GripperGrabAction::as_
actionlib::SimpleActionServer< pr2_gripper_sensor_msgs::PR2GripperGrabAction > as_
Definition: pr2_gripper_grab_action.cpp:179
argv
argv
actionlib::SimpleActionClient
simple_action_client.h
actionlib::SimpleActionClient::sendGoal
void sendGoal(const Goal &goal, SimpleDoneCallback done_cb=SimpleDoneCallback(), SimpleActiveCallback active_cb=SimpleActiveCallback(), SimpleFeedbackCallback feedback_cb=SimpleFeedbackCallback())
PR2GripperGrabAction
Definition: pr2_gripper_grab_action.cpp:174
actionlib::SimpleActionClient::getResult
ResultConstPtr getResult() const
ROS_ERROR
#define ROS_ERROR(...)
GripperClient
actionlib::SimpleActionClient< pr2_controllers_msgs::Pr2GripperCommandAction > GripperClient
Definition: pr2_gripper_grab_action.cpp:52
Gripper::open
void open(double position_open)
Definition: pr2_gripper_grab_action.cpp:105
PR2GripperGrabAction::result_
pr2_gripper_sensor_msgs::PR2GripperGrabResult result_
Definition: pr2_gripper_grab_action.cpp:183
actionlib::SimpleClientGoalState::SUCCEEDED
SUCCEEDED
Gripper::open
void open()
Definition: findContactActionTest.cpp:78
actionlib::SimpleActionClient::waitForResult
bool waitForResult(const ros::Duration &timeout=ros::Duration(0, 0))
Gripper::~Gripper
~Gripper()
Definition: pr2_gripper_grab_action.cpp:97
actionlib::SimpleActionServer::setPreempted
void setPreempted(const Result &result=Result(), const std::string &text=std::string(""))
Gripper
Definition: findContactActionTest.cpp:48
Gripper::hold
int hold(double holdForce)
Definition: pr2_gripper_grab_action.cpp:123
ForceClient
actionlib::SimpleActionClient< pr2_gripper_sensor_msgs::PR2GripperForceServoAction > ForceClient
Definition: pr2_gripper_grab_action.cpp:54
PR2GripperGrabAction::gripper
Gripper gripper
Definition: pr2_gripper_grab_action.cpp:184
actionlib::SimpleActionServer< pr2_gripper_sensor_msgs::PR2GripperGrabAction >
ContactClient
actionlib::SimpleActionClient< pr2_gripper_sensor_msgs::PR2GripperFindContactAction > ContactClient
Definition: pr2_gripper_grab_action.cpp:50
PR2GripperGrabAction::action_name_
std::string action_name_
Definition: pr2_gripper_grab_action.cpp:180
Gripper::contact_client_
ContactClient * contact_client_
Definition: findContactActionTest.cpp:51
Gripper::force_client_
ForceClient * force_client_
Definition: forceServoActionTest.cpp:55
Gripper::gripper_client_
GripperClient * gripper_client_
Definition: findContactActionTest.cpp:50
ros::spin
ROSCPP_DECL void spin()
PR2GripperGrabAction::PR2GripperGrabAction
PR2GripperGrabAction(std::string name)
Definition: pr2_gripper_grab_action.cpp:188
actionlib::SimpleActionClient::getState
SimpleClientGoalState getState() const
ros::NodeHandle::getNamespace
const std::string & getNamespace() const
main
int main(int argc, char **argv)
Definition: pr2_gripper_grab_action.cpp:280
ROS_INFO
#define ROS_INFO(...)
ros::Duration
PR2GripperGrabAction::executeCB
void executeCB(const pr2_gripper_sensor_msgs::PR2GripperGrabGoalConstPtr &goal)
Definition: pr2_gripper_grab_action.cpp:198
ros::NodeHandle


pr2_gripper_sensor_action
Author(s): Joe Romano
autogenerated on Thu Aug 8 2024 02:38:37