Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010 #include <ros/ros.h>
00011 #include <actionlib/client/simple_action_client.h>
00012 #include <face_recognition/FRClientGoal.h>
00013 #include <face_recognition/FaceRecognitionAction.h>
00014 #include <signal.h>
00015
00016 face_recognition::FaceRecognitionGoal goal;
00017 actionlib::SimpleActionClient<face_recognition::FaceRecognitionAction> * ac;
00018
00019
00020
00021 void doneCb(const actionlib::SimpleClientGoalState& state,
00022 const face_recognition::FaceRecognitionResultConstPtr& result)
00023 {
00024 ROS_INFO("Goal [%i] Finished in state [%s]", result->order_id,state.toString().c_str());
00025 if(state.toString() != "SUCCEEDED") return;
00026 if( result->order_id==0)
00027 ROS_INFO("%s was recognized with confidence %f", result->names[0].c_str(),result->confidence[0]);
00028 if( result->order_id==2)
00029 ROS_INFO("Pictures of %s were successfully added to the training images",result->names[0].c_str());
00030 }
00031
00032
00033 void activeCb()
00034 {
00035 ROS_INFO("Goal just went active");
00036 }
00037
00038
00039 void feedbackCb(const face_recognition::FaceRecognitionFeedbackConstPtr& feedback)
00040 {
00041 ROS_INFO("Received feedback from Goal [%d] ", feedback->order_id);
00042 if(feedback->order_id==1 )
00043 ROS_INFO("%s was recognized with confidence %f", feedback->names[0].c_str(),feedback->confidence[0]);
00044 if( feedback->order_id==2)
00045 ROS_INFO("A picture of %s was successfully added to the training images",feedback->names[0].c_str());
00046 }
00047
00048
00049 void frclientCallback(const face_recognition::FRClientGoalConstPtr& msg)
00050 {
00051
00052 ROS_INFO("request for sending goal [%i] is received", msg->order_id);
00053 goal.order_id = msg->order_id;
00054 goal.order_argument = msg->order_argument;
00055 ac->sendGoal(goal, &doneCb, &activeCb, &feedbackCb);
00056 }
00057
00058 void exit_handler(int s)
00059 {
00060 delete(ac);
00061 ros::shutdown();
00062 }
00063
00064
00065 int main (int argc, char **argv)
00066 {
00067 ros::init(argc, argv, "face_recognition_client");
00068 ros::NodeHandle n;
00069 ac = new actionlib::SimpleActionClient<face_recognition::FaceRecognitionAction>("face_recognition", true);
00070
00071 struct sigaction sigIntHandler;
00072 sigIntHandler.sa_handler = exit_handler;
00073 sigemptyset(&sigIntHandler.sa_mask);
00074 sigIntHandler.sa_flags = 0;
00075 sigaction(SIGINT, &sigIntHandler, NULL);
00076
00077 ac->waitForServer();
00078
00079 ros::Subscriber sub = n.subscribe("fr_order", 1, frclientCallback);
00080 ros::spin();
00081 return 0;
00082 }