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
00010
00011
00012
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
00017 cam_sub_ = it_.subscribeCamera("image_in", 1, &CamDetectionAlgNode::image_callback, this);
00018
00019
00020
00021
00022
00023
00024
00025
00026 }
00027
00028 CamDetectionAlgNode::~CamDetectionAlgNode(void)
00029 {
00030
00031 }
00032
00033 void CamDetectionAlgNode::mainNodeThread(void)
00034 {
00035
00036
00037
00038
00039
00040
00041
00042 }
00043
00044
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
00056 cv::Mat img_resized;
00057 cv::resize(cv_ptr_->image, img_resized, cv::Size(), width_resize_, height_resize_, cv::INTER_CUBIC);
00058
00059
00060 std::vector<img_dect> img_detections;
00061
00062
00063 cam_detector_.peopledetection(img_resized, img_detections);
00064 ROS_INFO("img_detections.size=%d",img_detections.size());
00065
00066
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
00081 cv_bridge::CvImage img_msg;
00082 img_msg.header = cv_ptr_->header;
00083 img_msg.encoding = cv_ptr_->encoding;
00084
00085
00086 cv::Mat outIm;
00087 CCamera_People_Detector drawer;
00088 drawer.drawpeopleweightsdetection(img_resized, outIm, img_detections);
00089 img_msg.image = outIm;
00090
00091
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
00104
00105
00106
00107
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
00122 int main(int argc,char *argv[])
00123 {
00124 return algorithm_base::main<CamDetectionAlgNode>(argc, argv, "cam_detection_alg_node");
00125 }