coordinator_node.h
Go to the documentation of this file.
00001 
00060 #ifndef _COORDINATOR_NODE_H_
00061 #define _COORDINATOR_NODE_H_
00062 
00063 // standard includes
00064 #include <sstream>
00065 #include <string>
00066 #include <vector>
00067 
00068 // ROS includes
00069 #include <ros/ros.h>
00070 
00071 // ROS message includes
00072 #include <cob_perception_msgs/DetectionArray.h>
00073 
00074 // actions
00075 #include <actionlib/server/simple_action_server.h>
00076 #include <cob_people_detection/getDetectionsAction.h>
00077 
00078 // services
00079 #include <std_srvs/Empty.h>
00080 #include <cob_people_detection/recognitionTrigger.h>
00081 
00082 // boost
00083 #include <boost/bind.hpp>
00084 #include <boost/thread/mutex.hpp>
00085 
00086 // external includes
00087 #include "cob_vision_utils/GlobalDefines.h"
00088 
00089 #include "cob_people_detection/face_recognizer.h"
00090 
00091 typedef actionlib::SimpleActionServer<cob_people_detection::getDetectionsAction> GetDetectionsServer;
00092 
00093 class CoordinatorNode
00094 {
00095 protected:
00096 
00097         ros::NodeHandle node_handle_; 
00098 
00099         boost::mutex active_action_mutex_; 
00100         boost::mutex last_detection_mutex_; 
00101         cob_perception_msgs::DetectionArray last_detection_message_; 
00102 
00103         bool sensor_message_gateway_open_; 
00104 
00105         // subscriber
00106         ros::Subscriber detection_sub_; 
00107 
00108         // actions
00109         GetDetectionsServer* get_detections_server_; 
00110 
00111         // services
00112         ros::ServiceServer service_server_start_recognition_; 
00113         ros::ServiceServer service_server_stop_recognition_; 
00114 
00115         // parameters
00116         std::string namespace_gateway_; 
00117 
00118         void detectionsCallback(const cob_perception_msgs::DetectionArray::ConstPtr& detection_array);
00119 
00120         void getDetectionsServerCallback(const cob_people_detection::getDetectionsGoalConstPtr& goal);
00121 
00122         bool startRecognitionCallback(cob_people_detection::recognitionTrigger::Request &req, cob_people_detection::recognitionTrigger::Response &res);
00123 
00124         bool stopRecognitionCallback(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res);
00125 
00126 public:
00127 
00128         CoordinatorNode(ros::NodeHandle nh);
00129         ~CoordinatorNode();
00130 };
00131 
00132 #endif // _COORDINATOR_NODE_H_


cob_people_detection
Author(s): Richard Bormann , Thomas Zwölfer
autogenerated on Fri Aug 28 2015 10:24:12