$search
00001 /* 00002 * Copyright (c) 2010 Oscar Martinez Mozos <omozos@googlemail.com> 00003 * Dejan Pangercic <pangercic -=- cs.tum.edu> (ROS maintaniner) 00004 * 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions are met: 00009 * 00010 * * Redistributions of source code must retain the above copyright 00011 * notice, this list of conditions and the following disclaimer. 00012 * * Redistributions in binary form must reproduce the above copyright 00013 * notice, this list of conditions and the following disclaimer in the 00014 * documentation and/or other materials provided with the distribution. 00015 * 00016 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00017 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00018 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00019 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00020 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00021 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00022 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00023 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00024 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00025 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00026 * POSSIBILITY OF SUCH DAMAGE. 00027 * 00028 * 00029 */ 00030 00052 //standards 00053 #include <iostream> 00054 #include <float.h> 00055 //People detector 00056 #include <PeopleDetector.h> 00057 00058 //ROS 00059 #include <ros/ros.h> 00060 #include <ros/node_handle.h> 00061 #include <sensor_msgs/LaserScan.h> 00062 00063 using namespace std; 00064 00065 00066 class PeopleDetectorNode 00067 { 00068 public: 00069 ros::NodeHandle nh_; 00070 //ROS msgs 00071 sensor_msgs::LaserScan scan_ouput_; 00072 //Subscribers/Publishers 00073 ros::Subscriber scan_; 00074 ros::Publisher scan_publish_; 00075 //Parameters 00076 string input_scan_topic_, output_scan_topic_; 00077 string hypotheses_filename_; 00078 int num_hypotheses_; 00079 double threshold_; 00080 FILE *f_hypotheses; 00081 int list_size_; 00082 //People Detector object 00083 PeopleDetector pd; 00084 00088 PeopleDetectorNode() : nh_("~") 00089 { 00090 nh_.param("input_scan_topic", input_scan_topic_, std::string("/scan")); 00091 nh_.param("output_scan_topic", output_scan_topic_, std::string("people_detected")); 00092 nh_.param("threshold", threshold_, 0.15); 00093 nh_.param("hypotheses_filename", hypotheses_filename_, std::string("")); 00094 nh_.param("num_hypotheses", num_hypotheses_, 100); 00095 nh_.param("list_size", list_size_, 500); 00096 if (hypotheses_filename_ == "") 00097 { 00098 ROS_ERROR("Provide hypotheses file!!"); 00099 exit(2); 00100 } 00101 scan_ = nh_.subscribe<sensor_msgs::LaserScan>(input_scan_topic_, 10, &PeopleDetectorNode::scan_cb, this); 00102 scan_publish_ = nh_.advertise<sensor_msgs::LaserScan> (output_scan_topic_, 1); 00103 } 00104 00108 ~PeopleDetectorNode() 00109 { 00110 fclose( f_hypotheses ); 00111 } 00112 00116 void init () 00117 { 00118 try 00119 { 00120 f_hypotheses = fopen(hypotheses_filename_.c_str(), "r"); 00121 if ( f_hypotheses == NULL ) 00122 { 00123 ROS_ERROR("ERROR opening hypotesis file %s", hypotheses_filename_.c_str()); 00124 throw -1; 00125 } 00126 } 00127 catch (int e) 00128 { 00129 } 00130 // configure the people detector object 00131 pd.load(f_hypotheses, num_hypotheses_); 00132 } 00133 00138 void scan_cb(const sensor_msgs::LaserScan::ConstPtr &msg) 00139 { 00140 scan_ouput_.intensities.clear(); 00141 scan_ouput_ = *msg; 00142 // This is a list of segments. 00143 // For more information have a look at ../common/dynamictable.h/hxx 00144 dyntab_segments *list_segments=NULL; 00145 int num_readings = msg->ranges.size(); 00146 double *angles = new double[num_readings]; // array of angles 00147 double *ranges = new double[num_readings]; // array of measurements 00148 00149 for (unsigned int i = 0; i < num_readings; i++) 00150 { 00151 ranges[i] = msg->ranges[i]; 00152 angles[i] = msg->angle_min + i * msg->angle_increment; 00153 } 00154 list_segments = new dyntab_segments (list_size_); 00155 // segment the scan 00156 pd.segmentScan(threshold_, num_readings, angles, ranges, list_segments); 00157 00158 // Classiy segments 00159 for (int i=0; i < list_segments->num(); i++) 00160 { 00161 Segment *s = list_segments->getElement(i); 00162 // discard segments with less than three points 00163 if ( s->num() < 3 ) 00164 { 00165 s->type = -1; 00166 } 00167 else 00168 { 00169 pd.classify(s); 00170 if ( s->type == 1) 00171 { 00172 printf("People found\n"); 00173 } 00174 else 00175 { 00176 printf("__NO__ People found\n"); 00177 // not a person 00178 } 00179 00180 } 00181 } 00182 //send out classification results (to rviz) 00183 for (int i=0; i < list_segments->num(); i++) 00184 { 00185 Segment *s = list_segments->getElement(i); 00186 for (int out = 0; out < s->num(); out++) 00187 { 00188 if (s->type == 1) 00189 scan_ouput_.intensities.push_back(1); 00190 else 00191 scan_ouput_.intensities.push_back(0); 00192 } 00193 } 00194 scan_publish_.publish(scan_ouput_); 00195 // delete the list of segments 00196 list_segments->setAutoDelete(true); 00197 delete list_segments; 00198 list_segments = NULL; 00199 00200 // free memory 00201 delete [] ranges; 00202 delete [] angles; 00203 } 00204 //end PeopleDetectorNode 00205 }; 00206 00207 00208 /* ---[ */ 00209 int main (int argc, char** argv) 00210 { 00211 ros::init (argc, argv, "people_detector_node"); 00212 PeopleDetectorNode pd_node; 00213 pd_node.init(); 00214 ros::spin (); 00215 return (0); 00216 } 00217 /* ]--- */ 00218