forceServoActionTest.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: findContactActionTest.cpp - example for using the findContact
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/PR2GripperForceServoAction.h>
42 
43 // Our Action interface type, provided as a typedef for convenience
45 // Our Action interface type, provided as a typedef for convenience
47 // Our Action interface type, provided as a typedef for convenience
49 
50 
51 class Gripper{
52 private:
56 
57 public:
58  //Action client initialization
60 
61  //Initialize the client for the Action interface to the gripper controller
62  //and tell the action client that we want to spin a thread by default
63  gripper_client_ = new GripperClient("r_gripper_sensor_controller/gripper_action", true);
64  contact_client_ = new ContactClient("r_gripper_sensor_controller/find_contact",true);
65  force_client_ = new ForceClient("r_gripper_sensor_controller/force_servo",true);
66 
67  //wait for the gripper action server to come up
68  while(!gripper_client_->waitForServer(ros::Duration(5.0))){
69  ROS_INFO("Waiting for the r_gripper_sensor_controller/gripper_action action server to come up");
70  }
71 
72  while(!contact_client_->waitForServer(ros::Duration(5.0))){
73  ROS_INFO("Waiting for the r_gripper_sensor_controller/find_contact action server to come up");
74  }
75 
76  while(!force_client_->waitForServer(ros::Duration(5.0))){
77  ROS_INFO("Waiting for the r_gripper_sensor_controller/force_servo action server to come up");
78  }
79  }
80 
82  delete gripper_client_;
83  delete contact_client_;
84  delete force_client_;
85  }
86 
87  //Open the gripper
88  void open(){
89  pr2_controllers_msgs::Pr2GripperCommandGoal open;
90  open.command.position = 0.08;
91  open.command.max_effort = -1.0;
92 
93  ROS_INFO("Sending open goal");
94  gripper_client_->sendGoal(open);
95  gripper_client_->waitForResult();
97  ROS_INFO("The gripper opened!");
98  else
99  ROS_INFO("The gripper failed to open.");
100  }
101 
102  //Close the gripper
103  void close(){
104  pr2_controllers_msgs::Pr2GripperCommandGoal squeeze;
105  squeeze.command.position = 0.0;
106  squeeze.command.max_effort = -1.0;
107 
108  ROS_INFO("Sending squeeze goal");
109  gripper_client_->sendGoal(squeeze);
110  gripper_client_->waitForResult();
111  if(gripper_client_->getState() == actionlib::SimpleClientGoalState::SUCCEEDED)
112  ROS_INFO("The gripper closed!");
113  else
114  ROS_INFO("The gripper failed to close.");
115  }
116 
117 
118 
119  //Hold somethign with a constant force in the gripper
120  void hold( double holdForce){
121  pr2_gripper_sensor_msgs::PR2GripperForceServoGoal squeeze;
122  squeeze.command.fingertip_force = holdForce; // hold with X N of force
123 
124  ROS_INFO("Sending hold goal");
125  force_client_->sendGoal(squeeze);
126  force_client_->waitForResult();
128  ROS_INFO("Stable force was achieved");
129  else
130  ROS_INFO("Stable force was NOT achieved");
131  }
132 
133 
134  //Find two contacts and go into force control mode
136  pr2_gripper_sensor_msgs::PR2GripperFindContactGoal findTwo;
137  findTwo.command.contact_conditions = findTwo.command.BOTH; // close until both fingers contact
138  findTwo.command.zero_fingertip_sensors = true; // zero fingertip sensor values before moving
139 
140 
141  ROS_INFO("Sending find 2 contact goal");
142  contact_client_->sendGoal(findTwo);
143  contact_client_->waitForResult(ros::Duration(5.0));
144  if(contact_client_->getState() == actionlib::SimpleClientGoalState::SUCCEEDED)
145  {
146  ROS_INFO("Contact found. Left: %d, Right: %d", contact_client_->getResult()->data.left_fingertip_pad_contact,
147  contact_client_->getResult()->data.right_fingertip_pad_contact);
148  ROS_INFO("Contact force. Left: %f, Right: %f", contact_client_->getResult()->data.left_fingertip_pad_force,
149  contact_client_->getResult()->data.right_fingertip_pad_force);
150  }
151  else
152  ROS_INFO("The gripper did not find a contact or could not maintain contact force.");
153  }
154 };
155 
156 int main(int argc, char** argv){
157  ros::init(argc, argv, "simple_gripper");
158 
159  Gripper gripper;
160 
161  gripper.open();
162  sleep(2.0);
163 
164  gripper.findTwoContacts();
165  gripper.hold(4.0); // hold with 10 N of force
166 
167 //gripper.close();
168 
169  return 0;
170 }
actionlib::SimpleActionClient< pr2_gripper_sensor_msgs::PR2GripperForceServoAction > ForceClient
actionlib::SimpleActionClient< pr2_gripper_sensor_msgs::PR2GripperFindContactAction > ContactClient
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)
#define ROS_INFO(...)
actionlib::SimpleActionClient< pr2_controllers_msgs::Pr2GripperCommandAction > GripperClient
ContactClient * contact_client_
ForceClient * force_client_
void sendGoal(const Goal &goal, SimpleDoneCallback done_cb=SimpleDoneCallback(), SimpleActiveCallback active_cb=SimpleActiveCallback(), SimpleFeedbackCallback feedback_cb=SimpleFeedbackCallback())
GripperClient * gripper_client_
int main(int argc, char **argv)
void hold(double holdForce)
SimpleClientGoalState getState() const
ResultConstPtr getResult() const


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