face_rec_client.cpp
Go to the documentation of this file.
00001 /* Copyright 2012 Pouyan Ziafati, University of Luxembourg and Utrecht University
00002 
00003 * actionlib client example for the face_recognition simple actionlib server. The client subscribes to face_recognition::FRClientGoal messages. Each FRClientGoal message contains an order_id and an order_argument which specify a goal to be executed by the face_recognition server. After receiving a message, the client sends the corresponding goal to the server. By registering relevant call back functions, the client receives feedback and result information from the execution of goals in the server and prints such information on the terminal.
00004 
00005 *Provided by modifying the ROS wiki tutorial: "actionlib_tutorials/Tutorials/Writing a Callback Based Simple Action Client (last edited 2010-09-13 17:32:34 by VijayPradeep)"
00006 
00007 *License: Creative Commons Attribution 3.0. 
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; //Goal message
00017 actionlib::SimpleActionClient<face_recognition::FaceRecognitionAction> * ac; //action lib client
00018 
00019 
00020 // Called once when the goal completes
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 // Called once when the goal becomes active
00033 void activeCb()
00034 {
00035   ROS_INFO("Goal just went active");
00036 }
00037 
00038 // Called every time feedback is received for the goal
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 //called for every FRClientGoal message received by the client. Client processes each message and sends the corresponding goal to the server and registers feedback and result and status call back functions.
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 //shut down
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   //for proper shutdown exit_handler is used
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   //wait for the server 
00077   ac->waitForServer();
00078   //subscribe to the topic of interest 
00079   ros::Subscriber sub = n.subscribe("fr_order", 1, frclientCallback);
00080   ros::spin();
00081   return 0;
00082 }


face_recognition
Author(s): Pouyan Ziafati
autogenerated on Thu Jun 6 2019 18:29:21