face_normalizer_node.h
Go to the documentation of this file.
00001 
00061 #ifndef __FACE_NORMALIZER_NODE_H__
00062 #define __FACE_NORMALIZER_NODE_H__
00063 
00064 #ifdef __LINUX__
00065 #include "cob_people_detection/face_normalizer.h"
00066 #else
00067 #endif
00068 
00069 // ROS includes
00070 #include <ros/ros.h>
00071 #include <ros/package.h>                // use as: directory_ = ros::package::getPath("cob_people_detection") + "/common/files/windows/";
00072 // ROS message includes
00073 #include <sensor_msgs/Image.h>
00074 #include <geometry_msgs/Point.h>
00075 #include <cob_perception_msgs/DetectionArray.h>
00076 #include <cob_perception_msgs/ColorDepthImageArray.h>
00077 //#include <cob_perception_msgs/ColorDepthImageCropArray.h>
00078 
00079 // Actions
00080 #include <actionlib/server/simple_action_server.h>
00081 #include <cob_people_detection/loadModelAction.h>
00082 
00083 #include "cob_people_detection/face_normalizer.h"
00084 
00085 namespace ipa_PeopleDetector
00086 {
00087 
00088 class FaceNormalizerNode
00089 {
00090 public:
00091 
00094         FaceNormalizerNode(ros::NodeHandle nh);
00095         ~FaceNormalizerNode(void); 
00096 
00097 
00098 protected:
00099 
00101         void facePositionsCallback(const cob_perception_msgs::ColorDepthImageArray::ConstPtr& face_positions);
00102 
00103         ros::NodeHandle node_handle_;
00104 
00105         ros::Subscriber face_position_subscriber_; 
00106 
00107         ros::Publisher norm_face_publisher_; 
00108 
00109         FaceNormalizer face_normalizer_; 
00110 
00111 
00112         // parameters
00113         std::string debug_directory_; 
00114 
00115 };
00116 
00117 }
00118 
00119 #endif // __FACE_NORMALIZER_NODE_H__


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