Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #include <ros/ros.h>
00031 #include <actionlib/client/simple_action_client.h>
00032 #include <actionlib/client/terminal_state.h>
00033
00034
00035 #include <pcl_cloud_tools/GetClustersAction.h>
00036
00037
00038 #include <amtec/SetPosition.h>
00039
00040 boost::shared_ptr<const pcl_cloud_tools::GetClustersResult> getClusters(int ec_goal)
00041 {
00042
00043 typedef actionlib::SimpleActionClient<pcl_cloud_tools::GetClustersAction> GetClustersClient;
00044 GetClustersClient gcc("/extract_clusters/get_clusters", true);
00045 while(!gcc.waitForServer())
00046 {
00047 ROS_INFO("Waiting for /extract_clusters/get_clusters server to come up");
00048 }
00049
00050 pcl_cloud_tools::GetClustersGoal goal;
00051 goal.ec_goal = ec_goal;
00052
00053 gcc.sendGoal(goal);
00054 gcc.waitForResult(ros::Duration(5.0));
00055 if (gcc.getState() == actionlib::SimpleClientGoalState::SUCCEEDED)
00056 ROS_INFO("/extract_clusters/get_clusters SUCCEEDED");
00057 boost::shared_ptr<const pcl_cloud_tools::GetClustersResult> result = gcc.getResult();
00058 return result;
00059 }
00060
00061
00062 int main (int argc, char **argv)
00063 {
00064 ros::init(argc, argv, "amtec_acquire_data");
00065 ros::NodeHandle nh;
00066
00067 boost::shared_ptr<const pcl_cloud_tools::GetClustersResult> result = getClusters(0);
00068 if (result->clusters.size () == 0)
00069 {
00070 ROS_ERROR("No clusters found, returning");
00071 return -1;
00072 }
00073 else
00074 {
00075 ROS_INFO("%ld clusters found", result->clusters.size ());
00076 }
00077
00078
00079 ros::ServiceClient client = nh.serviceClient<amtec::SetPosition>("/amtec/set_position");
00080 amtec::SetPosition srv;
00081 srv.request.position_pan = 0.0;
00082 srv.request.position_pan = atof(argv[1]);
00083 if (client.call(srv))
00084 {
00085 ROS_INFO("Successful call to service /amtec/set_position");
00086 }
00087 else
00088 {
00089 ROS_ERROR("Failed to call service /amtec/set_position");
00090 return -1;
00091 }
00092 return 0;
00093 }