gripper_client.cpp
Go to the documentation of this file.
1 #include <ros/ros.h>
3 
4 #include <xarm_gripper/MoveAction.h>
5 
6 
7 int main (int argc, char **argv)
8 {
9  ros::init(argc, argv, "test_gripper");
10 
11  // create the action client
12  // true causes the client to spin its own thread
13  actionlib::SimpleActionClient<xarm_gripper::MoveAction> ac("xarm/gripper_move", true);
14 
15  ROS_INFO("Waiting for action server to start.");
16  // wait for the action server to start
17  ac.waitForServer(); //will wait for infinite time
18 
19  ROS_INFO("Action server started, sending goal.");
20  // send a goal to the action
21  xarm_gripper::MoveGoal goal;
22  if(argc<3)
23  {
24  ROS_WARN("argment 1: target_pulse, argument 2: pulse_speed, Not fully specified.");
25  ROS_INFO("Use default target_pulse: 450, pulse_speed: 1500");
26  goal.target_pulse = 450;
27  goal.pulse_speed = 1500;
28  }
29  else
30  {
31  goal.target_pulse = std::atof(argv[1]);
32  goal.pulse_speed = std::atof(argv[2]);
33  }
34  ac.sendGoal(goal);
35 
36  //wait for the action to return
37  bool finished_before_timeout = ac.waitForResult(ros::Duration(5.0));
38 
39  if (finished_before_timeout)
40  {
42  ROS_INFO("Action finished: %s",state.toString().c_str());
43  }
44  else
45  {
46  ROS_INFO("Action did not finish before the time out.");
47  ac.cancelAllGoals();
48  }
49  //exit
50  return 0;
51 }
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_WARN(...)
std::string toString() const
#define ROS_INFO(...)
int main(int argc, char **argv)
void sendGoal(const Goal &goal, SimpleDoneCallback done_cb=SimpleDoneCallback(), SimpleActiveCallback active_cb=SimpleActiveCallback(), SimpleFeedbackCallback feedback_cb=SimpleFeedbackCallback())
SimpleClientGoalState getState() const


xarm_gripper
Author(s): jason_peng
autogenerated on Sat May 8 2021 02:51:44