00001 #include <ros/ros.h>
00002 #include <actionlib/client/simple_action_client.h>
00003 #include <actionlib/client/terminal_state.h>
00004 #include "pr2_create_object_model/ModelObjectInHandAction.h"
00005
00006 int main (int argc, char **argv)
00007 {
00008 ros::init(argc, argv, "ping_create_object_model_server");
00009
00010
00011
00012 actionlib::SimpleActionClient<pr2_create_object_model::ModelObjectInHandAction> ac("create_object_model_server/model_object_in_hand_action", true);
00013
00014 ROS_INFO("Waiting for action server to start.");
00015
00016 ac.waitForServer();
00017
00018 ROS_INFO("Action server started, sending goal.");
00019
00020 pr2_create_object_model::ModelObjectInHandGoal goal;
00021 goal.arm_name = std::string("right_arm");
00022 goal.keep_level = 0;
00023 goal.move_arm = 1;
00024 ac.sendGoal(goal);
00025
00026
00027 bool finished_before_timeout = ac.waitForResult(ros::Duration(30.0));
00028
00029 if (finished_before_timeout)
00030 {
00031 actionlib::SimpleClientGoalState state = ac.getState();
00032 ROS_INFO("Action finished: %s",state.toString().c_str());
00033 }
00034 else
00035 ROS_INFO("Action did not finish before the time out.");
00036
00037
00038 return 0;
00039 }