robotiq_action_server_client_test.cpp
Go to the documentation of this file.
00001 #include <ros/ros.h>
00002 #include <actionlib/client/simple_action_client.h>
00003 #include <actionlib/client/terminal_state.h>
00004 #include <control_msgs/GripperCommandAction.h>
00005 
00006 int main (int argc, char **argv)
00007 {
00008   ros::init(argc, argv, "test_robotiq_action_server");
00009 
00010   ros::NodeHandle pnh("~");
00011 
00012   std::string gripper_name;
00013   pnh.param<std::string>("gripper_name", gripper_name, "gripper");
00014 
00015   // create the action client
00016   // true causes the client to spin its own thread
00017   actionlib::SimpleActionClient<control_msgs::GripperCommandAction> ac(gripper_name, true);
00018 
00019   ROS_INFO("Waiting for action server to start.");
00020   // wait for the action server to start
00021   ac.waitForServer(); //will wait for infinite time
00022 
00023   ROS_INFO("Action server started, sending goal.");
00024   // send a goal to the action
00025   control_msgs::GripperCommandGoal goal;
00026   goal.command.position = -0.01;
00027   goal.command.max_effort = 100.0;
00028   ac.sendGoal(goal);
00029 
00030   //wait for the action to return
00031   bool finished_before_timeout = ac.waitForResult(ros::Duration(30.0));
00032 
00033   if (finished_before_timeout)
00034   {
00035     actionlib::SimpleClientGoalState state = ac.getState();
00036     ROS_INFO("Action finished: %s",state.toString().c_str());
00037   }
00038   else
00039     ROS_INFO("Action did not finish before the time out.");
00040 
00041   //exit
00042   return 0;
00043 }


robotiq_action_server
Author(s): Jonathan Meyer
autogenerated on Thu Aug 27 2015 14:44:24