findContactActionTest.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>
41 
42 // Our Action interface type, provided as a typedef for convenience
44 // Our Action interface type, provided as a typedef for convenience
46 
47 
48 class Gripper{
49 private:
52 
53 public:
54  //Action client initialization
56 
57  //Initialize the client for the Action interface to the gripper controller
58  //and tell the action client that we want to spin a thread by default
59  gripper_client_ = new GripperClient("r_gripper_sensor_controller/gripper_action", true);
60  contact_client_ = new ContactClient("r_gripper_sensor_controller/find_contact",true);
61 
62  //wait for the gripper action server to come up
63  while(!gripper_client_->waitForServer(ros::Duration(5.0))){
64  ROS_INFO("Waiting for the r_gripper_sensor_controller/gripper_action action server to come up");
65  }
66 
67  while(!contact_client_->waitForServer(ros::Duration(5.0))){
68  ROS_INFO("Waiting for the r_gripper_sensor_controller/find_contact action server to come up");
69  }
70  }
71 
73  delete gripper_client_;
74  delete contact_client_;
75  }
76 
77  //Open the gripper
78  void open(){
79  pr2_controllers_msgs::Pr2GripperCommandGoal open;
80  open.command.position = 0.08;
81  open.command.max_effort = -1.0;
82 
83  ROS_INFO("Sending open goal");
84  gripper_client_->sendGoal(open);
85  gripper_client_->waitForResult();
87  ROS_INFO("The gripper opened!");
88  else
89  ROS_INFO("The gripper failed to open.");
90  }
91 
92  //Find a single finger contact and go into position control mode
94  pr2_gripper_sensor_msgs::PR2GripperFindContactGoal findOne;
95  findOne.command.contact_conditions = findOne.command.EITHER;
96  findOne.command.zero_fingertip_sensors = true;
97 
98 
99  ROS_INFO("Sending find 1 contact goal");
100  contact_client_->sendGoal(findOne);
101  contact_client_->waitForResult();
102  if(contact_client_->getState() == actionlib::SimpleClientGoalState::SUCCEEDED)
103  {
104  ROS_INFO("Contact found. Left: %d, Right: %d", contact_client_->getResult()->data.left_fingertip_pad_contact,
105  contact_client_->getResult()->data.right_fingertip_pad_contact);
106  ROS_INFO("Contact force. Left: %f, Right: %f", contact_client_->getResult()->data.left_fingertip_pad_force,
107  contact_client_->getResult()->data.right_fingertip_pad_force);
108  }
109  else
110  ROS_INFO("The gripper did not find a contact.");
111  }
112 
113 
114 
115  //Find two contacts and go into force control mode
117  pr2_gripper_sensor_msgs::PR2GripperFindContactGoal findTwo;
118  findTwo.command.contact_conditions = findTwo.command.BOTH; // close until both fingers contact
119  findTwo.command.zero_fingertip_sensors = true; // zero fingertip sensor values before moving
120 
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 or could not maintain contact force.");
134  }
135 };
136 
137 int main(int argc, char** argv){
138  ros::init(argc, argv, "simple_gripper");
139 
140  Gripper gripper;
141 
142  gripper.open();
143  sleep(1.0);
144  gripper.findOneContact();
145  sleep(2.0);
146 
147  gripper.open();
148  sleep(1.0);
149  gripper.findTwoContacts();
150 
151 
152  return 0;
153 }
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::PR2GripperFindContactAction > ContactClient
int main(int argc, char **argv)
#define ROS_INFO(...)
actionlib::SimpleActionClient< pr2_controllers_msgs::Pr2GripperCommandAction > GripperClient
ContactClient * contact_client_
void sendGoal(const Goal &goal, SimpleDoneCallback done_cb=SimpleDoneCallback(), SimpleActiveCallback active_cb=SimpleActiveCallback(), SimpleFeedbackCallback feedback_cb=SimpleFeedbackCallback())
GripperClient * gripper_client_
SimpleClientGoalState getState() const
ResultConstPtr getResult() const


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