robotiq_2f_gripper_action_server_client_test.cpp
Go to the documentation of this file.
1 #include <ros/ros.h>
4 #include <control_msgs/GripperCommandAction.h>
5 
6 int main (int argc, char **argv)
7 {
8  ros::init(argc, argv, "test_robotiq_2f_gripper_action_server");
9 
10  ros::NodeHandle pnh("~");
11 
12  std::string gripper_name;
13  pnh.param<std::string>("gripper_name", gripper_name, "gripper");
14 
15  // create the action client
16  // true causes the client to spin its own thread
18 
19  ROS_INFO("Waiting for action server to start.");
20  // wait for the action server to start
21  ac.waitForServer(); //will wait for infinite time
22 
23  ROS_INFO("Action server started, sending goal.");
24  // send a goal to the action
26  goal.command.position = -0.01;
27  goal.command.max_effort = 100.0;
28  ac.sendGoal(goal);
29 
30  //wait for the action to return
31  bool finished_before_timeout = ac.waitForResult(ros::Duration(30.0));
32 
33  if (finished_before_timeout)
34  {
35  actionlib::SimpleClientGoalState state = ac.getState();
36  ROS_INFO("Action finished: %s",state.toString().c_str());
37  }
38  else
39  ROS_INFO("Action did not finish before the time out.");
40 
41  //exit
42  return 0;
43 }
int main(int argc, char **argv)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
std::string toString() const
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
control_msgs::GripperCommandGoal GripperCommandGoal


robotiq_2f_gripper_action_server
Author(s): Jonathan Meyer
autogenerated on Tue Jun 1 2021 02:29:56