cam_detection_alg_node.cpp
Go to the documentation of this file.
00001 #include "cam_detection_alg_node.h"
00002 
00003 CamDetectionAlgNode::CamDetectionAlgNode(void) :
00004   algorithm_base::IriBaseAlgorithm<CamDetectionAlgorithm>(),
00005   it_(public_node_handle_),
00006   width_resize_(0.5f),
00007   height_resize_(0.5f)
00008 {
00009   //init class attributes if necessary
00010   //this->loop_rate_ = 2;//in [Hz]
00011 
00012   // [init publishers]
00013   detection_publisher_ = public_node_handle_.advertise<iri_perception_msgs::img_detection>("detection", 100);
00014   debug_img_publisher_ = it_.advertise("debug_image", 1);
00015   
00016   // [init subscribers]
00017   cam_sub_ = it_.subscribeCamera("image_in", 1, &CamDetectionAlgNode::image_callback, this);
00018 
00019   // [init services]
00020   
00021   // [init clients]
00022   
00023   // [init action servers]
00024   
00025   // [init action clients]
00026 }
00027 
00028 CamDetectionAlgNode::~CamDetectionAlgNode(void)
00029 {
00030   // [free dynamic memory]
00031 }
00032 
00033 void CamDetectionAlgNode::mainNodeThread(void)
00034 {
00035   // [fill msg structures]
00036   
00037   // [fill srv structure and make request to the server]
00038   
00039   // [fill action structure and make request to the action server]
00040 
00041   // [publish messages]
00042 }
00043 
00044 /*  [subscriber callbacks] */
00045 void CamDetectionAlgNode::image_callback(const sensor_msgs::ImageConstPtr& image_msg, 
00046                                          const sensor_msgs::CameraInfoConstPtr& info_msg)
00047 {
00048   ROS_INFO("CamDetectionAlgNode::image_callback: New Message Received"); 
00049 
00050   alg_.lock();
00051     try
00052     {
00053       cv_ptr_ = cv_bridge::toCvCopy(image_msg, sensor_msgs::image_encodings::BGR8);
00054 
00055       //resize original image size and detections
00056       cv::Mat img_resized;
00057       cv::resize(cv_ptr_->image, img_resized, cv::Size(), width_resize_, height_resize_, cv::INTER_CUBIC);
00058 
00059       // where the detections will be saved, new structure
00060       std::vector<img_dect> img_detections;
00061 
00062       // execute camera people detection algorithm
00063       cam_detector_.peopledetection(img_resized, img_detections);
00064       ROS_INFO("img_detections.size=%d",img_detections.size());
00065 
00066       // fill up message with detections result
00067       iri_perception_msgs::img_detection img_detection_msg;
00068       img_detection_msg.header = cv_ptr_->header;
00069       img_detection_msg.dets.resize(img_detections.size());
00070       for(unsigned int ii=0; ii<img_detections.size(); ii++)
00071       {
00072         img_detection_msg.dets[ii].id     = img_detections[ii].id;
00073         img_detection_msg.dets[ii].x      = img_detections[ii].Bbox.x;
00074         img_detection_msg.dets[ii].y      = img_detections[ii].Bbox.y;
00075         img_detection_msg.dets[ii].width  = img_detections[ii].Bbox.width;
00076         img_detection_msg.dets[ii].height = img_detections[ii].Bbox.height;
00077         img_detection_msg.dets[ii].score  = img_detections[ii].score;
00078       }
00079 
00080       // output image with detections
00081       cv_bridge::CvImage img_msg;
00082       img_msg.header   = cv_ptr_->header;
00083       img_msg.encoding = cv_ptr_->encoding;
00084 
00085       // draw image with the new structure
00086       cv::Mat outIm;
00087       CCamera_People_Detector drawer;
00088       drawer.drawpeopleweightsdetection(img_resized, outIm, img_detections);
00089       img_msg.image = outIm;
00090 
00091       // publish messages
00092       detection_publisher_.publish(img_detection_msg);
00093       debug_img_publisher_.publish(img_msg.toImageMsg());
00094     }
00095     catch (cv_bridge::Exception& e)
00096     {
00097       ROS_ERROR("cv_bridge exception: %s", e.what());
00098       return;
00099     }
00100   alg_.unlock();
00101 }
00102 
00103 /*  [service callbacks] */
00104 
00105 /*  [action callbacks] */
00106 
00107 /*  [action requests] */
00108 
00109 void CamDetectionAlgNode::node_config_update(Config &config, uint32_t level)
00110 {
00111   alg_.lock();
00112     width_resize_  = config.width_resize;
00113     height_resize_ = config.height_resize;
00114   alg_.unlock();
00115 }
00116 
00117 void CamDetectionAlgNode::addNodeDiagnostics(void)
00118 {
00119 }
00120 
00121 /* main function */
00122 int main(int argc,char *argv[])
00123 {
00124   return algorithm_base::main<CamDetectionAlgNode>(argc, argv, "cam_detection_alg_node");
00125 }


iri_cam_detection
Author(s):
autogenerated on Fri Dec 6 2013 20:19:06