src
positionActionTest.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: positionActionTest.cpp - example for using the position
35
// action server
36
37
#include <
ros/ros.h
>
38
#include <pr2_controllers_msgs/Pr2GripperCommandAction.h>
39
#include <
actionlib/client/simple_action_client.h
>
40
41
// Our Action interface type, provided as a typedef for convenience
42
typedef
actionlib::SimpleActionClient<pr2_controllers_msgs::Pr2GripperCommandAction>
GripperClient
;
43
44
class
Gripper
{
45
private
:
46
GripperClient
*
gripper_client_
;
47
48
public
:
49
//Action client initialization
50
Gripper
(){
51
52
//Initialize the client for the Action interface to the gripper controller
53
//and tell the action client that we want to spin a thread by default
54
gripper_client_
=
new
GripperClient
(
"r_gripper_sensor_controller/gripper_action"
,
true
);
55
56
//wait for the gripper action server to come up
57
while
(!
gripper_client_
->
waitForServer
(
ros::Duration
(5.0))){
58
ROS_INFO
(
"Waiting for the r_gripper_sensor_controller/gripper_action action server to come up"
);
59
}
60
}
61
62
~Gripper
(){
63
delete
gripper_client_
;
64
}
65
66
//Open the gripper
67
void
open
(){
68
pr2_controllers_msgs::Pr2GripperCommandGoal
open
;
69
open
.command.position = 0.08;
70
open
.command.max_effort = -1.0;
71
72
ROS_INFO
(
"Sending open goal"
);
73
gripper_client_
->
sendGoal
(
open
);
74
gripper_client_
->
waitForResult
();
75
if
(
gripper_client_
->
getState
() ==
actionlib::SimpleClientGoalState::SUCCEEDED
)
76
ROS_INFO
(
"The gripper opened!"
);
77
else
78
ROS_INFO
(
"The gripper failed to open."
);
79
}
80
81
//Close the gripper
82
void
close
(){
83
pr2_controllers_msgs::Pr2GripperCommandGoal squeeze;
84
squeeze.command.position = 0.0;
85
squeeze.command.max_effort = -1.0;
86
87
ROS_INFO
(
"Sending squeeze goal"
);
88
gripper_client_
->
sendGoal
(squeeze);
89
gripper_client_
->
waitForResult
();
90
if
(
gripper_client_
->
getState
() ==
actionlib::SimpleClientGoalState::SUCCEEDED
)
91
ROS_INFO
(
"The gripper closed!"
);
92
else
93
ROS_INFO
(
"The gripper failed to close."
);
94
}
95
};
96
97
int
main
(
int
argc,
char
** argv){
98
ros::init
(argc,
argv
,
"simple_gripper"
);
99
100
Gripper
gripper;
101
102
gripper.
open
();
103
gripper.
close
();
104
105
return
0;
106
}
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros.h
actionlib::SimpleActionClient::waitForServer
bool waitForServer(const ros::Duration &timeout=ros::Duration(0, 0)) const
Gripper::Gripper
Gripper()
Definition:
positionActionTest.cpp:50
main
int main(int argc, char **argv)
Definition:
positionActionTest.cpp:97
argv
argv
actionlib::SimpleActionClient
GripperClient
actionlib::SimpleActionClient< pr2_controllers_msgs::Pr2GripperCommandAction > GripperClient
Definition:
positionActionTest.cpp:42
simple_action_client.h
actionlib::SimpleActionClient::sendGoal
void sendGoal(const Goal &goal, SimpleDoneCallback done_cb=SimpleDoneCallback(), SimpleActiveCallback active_cb=SimpleActiveCallback(), SimpleFeedbackCallback feedback_cb=SimpleFeedbackCallback())
actionlib::SimpleClientGoalState::SUCCEEDED
SUCCEEDED
Gripper::open
void open()
Definition:
positionActionTest.cpp:67
actionlib::SimpleActionClient::waitForResult
bool waitForResult(const ros::Duration &timeout=ros::Duration(0, 0))
Gripper::close
void close()
Definition:
positionActionTest.cpp:82
Gripper::~Gripper
~Gripper()
Definition:
positionActionTest.cpp:62
Gripper
Definition:
findContactActionTest.cpp:48
Gripper::gripper_client_
GripperClient * gripper_client_
Definition:
findContactActionTest.cpp:50
actionlib::SimpleActionClient::getState
SimpleClientGoalState getState() const
ROS_INFO
#define ROS_INFO(...)
ros::Duration
pr2_gripper_sensor_action
Author(s): Joe Romano
autogenerated on Thu Aug 8 2024 02:38:37