38 #include <pr2_controllers_msgs/Pr2GripperCommandAction.h> 54 gripper_client_ =
new GripperClient(
"r_gripper_sensor_controller/gripper_action",
true);
58 ROS_INFO(
"Waiting for the r_gripper_sensor_controller/gripper_action action server to come up");
68 pr2_controllers_msgs::Pr2GripperCommandGoal
open;
69 open.command.position = 0.08;
70 open.command.max_effort = -1.0;
78 ROS_INFO(
"The gripper failed to open.");
83 pr2_controllers_msgs::Pr2GripperCommandGoal squeeze;
84 squeeze.command.position = 0.0;
85 squeeze.command.max_effort = -1.0;
93 ROS_INFO(
"The gripper failed to close.");
97 int main(
int argc,
char** argv){
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_controllers_msgs::Pr2GripperCommandAction > GripperClient
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)
SimpleClientGoalState getState() const