49 #include <boost/filesystem.hpp>
50 #include <boost/thread/mutex.hpp>
52 #include <people_msgs/PositionMeasurement.h>
53 #include <people_msgs/PositionMeasurementArray.h>
59 #include <sensor_msgs/CameraInfo.h>
60 #include <sensor_msgs/Image.h>
61 #include <stereo_msgs/DisparityImage.h>
65 #include <sensor_msgs/PointCloud.h>
66 #include <geometry_msgs/Point32.h>
68 #include <opencv2/core/core_c.h>
69 #include <opencv2/highgui.hpp>
70 #include <opencv2/highgui/highgui_c.h>
77 #include <face_detector/FaceDetectorAction.h>
79 #include <yaml-cpp/yaml.h>
83 bool fexists(
const std::string& filename)
85 std::ifstream ifile(filename);
86 return ifile.is_open();
91 std::string param_value;
92 local_nh.
param(
"classifier_filename", param_value, std::string(
""));
98 std::vector<std::string> folders;
100 if (local_nh.
hasParam(
"classifier_folders"))
102 local_nh.
param(
"classifier_folders", folders);
106 YAML::Node folders_yaml = YAML::LoadFile(
ros::package::getPath(
"face_detector") +
"/param/default_folders.yaml");
107 for (YAML::const_iterator it = folders_yaml.begin(); it != folders_yaml.end(); ++it)
109 folders.push_back(it->as<std::string>());
113 for (
const std::string& folder : folders)
115 std::string path = folder +
"/" + param_value;
122 ROS_FATAL(
"Cascade file %s doesn't exist.", param_value.c_str());
169 <sensor_msgs::Image, stereo_msgs::DisparityImage, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo>
172 <sensor_msgs::Image, stereo_msgs::DisparityImage, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo>
181 <sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo>
184 <sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo>
226 people_msgs::PositionMeasurement
pos;
229 std::map<std::string, RestampedPositionMeasurement>
pos_list_;
262 double face_size_min_m, face_size_max_m, max_face_z_m, face_sep_dist_m;
280 local_nh.
param(
"queue_size", queue_size, 5);
281 local_nh.
param(
"approximate_sync", approx,
false);
288 cv::namedWindow(
"Face detector: Face Detection", CV_WINDOW_AUTOSIZE);
295 face_size_min_m, face_size_max_m, max_face_z_m, face_sep_dist_m);
312 local_nh.
param(
"fixed_frame",
fixed_frame_, std::string(
"camera_rgb_optical_frame"));
319 this, _1, _2, _3, _4));
326 this, _1, _2, _3, _4));
332 face_size_min_m, face_size_max_m, max_face_z_m, face_sep_dist_m);
348 this, _1, _2, _3, _4));
355 this, _1, _2, _3, _4));
363 ROS_INFO_STREAM_NAMED(
"face_detector",
"You must subscribe to one of FaceDetector's outbound topics "
364 "or else it will not publish anything.");
371 "face_detector/people_tracker_measurements_array", 1, pos_pub_connect_cb, pos_pub_connect_cb);
374 cloud_pub_connect_cb, cloud_pub_connect_cb);
390 cv::destroyWindow(
"Face detector: Face Detection");
409 "so it will no longer publish anything.");
435 "so it will no longer publish anything.");
514 const sensor_msgs::Image::ConstPtr& depth_image,
515 const sensor_msgs::CameraInfo::ConstPtr& c1_info,
516 const sensor_msgs::CameraInfo::ConstPtr& c2_info)
523 result_.face_positions.clear();
533 cv::Mat depth_32fc1 = cv_depth_ptr->image;
534 if (depth_image->encoding !=
"32FC1")
536 cv_depth_ptr->image.convertTo(depth_32fc1, CV_32FC1, 0.001);
547 struct timeval timeofday;
548 gettimeofday(&timeofday, NULL);
552 gettimeofday(&timeofday, NULL);
569 const stereo_msgs::DisparityImage::ConstPtr& disp_image,
570 const sensor_msgs::CameraInfo::ConstPtr& c1_info,
571 const sensor_msgs::CameraInfo::ConstPtr& c2_info)
578 result_.face_positions.clear();
596 struct timeval timeofday;
597 gettimeofday(&timeofday, NULL);
602 gettimeofday(&timeofday, NULL);
611 void matchAndDisplay(std::vector<Box2D3D> faces_vector, std_msgs::Header header)
613 bool found_faces =
false;
616 sensor_msgs::PointCloud cloud;
617 cloud.header.stamp =
header.stamp;
618 cloud.header.frame_id =
header.frame_id;
620 if (faces_vector.size() > 0)
624 std::map<std::string, RestampedPositionMeasurement>::iterator it;
642 (*it).second.pos.header.stamp =
header.stamp;
643 (*it).second.pos.pos.x = loc[0];
644 (*it).second.pos.pos.y = loc[1];
645 (*it).second.pos.pos.z = loc[2];
657 people_msgs::PositionMeasurement pos;
658 people_msgs::PositionMeasurementArray pos_array;
660 for (uint iface = 0; iface < faces_vector.size(); iface++)
662 one_face = &faces_vector[iface];
669 pos.header.stamp =
header.stamp;
671 pos.pos.x = one_face->center3d.x;
672 pos.pos.y = one_face->center3d.y;
673 pos.pos.z = one_face->center3d.z;
674 pos.header.frame_id =
header.frame_id;
676 pos.initialization = 1;
677 pos.covariance[0] = 0.04;
678 pos.covariance[1] = 0.0;
679 pos.covariance[2] = 0.0;
680 pos.covariance[3] = 0.0;
681 pos.covariance[4] = 0.04;
682 pos.covariance[5] = 0.0;
683 pos.covariance[6] = 0.0;
684 pos.covariance[7] = 0.0;
685 pos.covariance[8] = 0.04;
693 std::map<std::string, RestampedPositionMeasurement>::iterator close_it =
pos_list_.end();
696 dist = pow((*it).second.pos.pos.x - pos.pos.x, 2.0) +
697 pow((*it).second.pos.pos.y - pos.pos.y, 2.0) +
698 pow((*it).second.pos.pos.z - pos.pos.z, 2.0);
699 if (dist <= faces_->face_sep_dist_m_ && dist < mindist)
707 pos.object_id = (*close_it).second.pos.object_id;
708 if (mindist < (*close_it).second.dist)
710 (*close_it).second.restamp =
header.stamp;
711 (*close_it).second.dist = mindist;
712 (*close_it).second.pos = pos;
719 pos.object_id =
static_cast<std::ostringstream*
>(&(std::ostringstream() <<
max_id_))->str();
720 ROS_INFO_STREAM_NAMED(
"face_detector",
"Didn't find face to match, starting new ID " << pos.object_id);
722 result_.face_positions.push_back(pos);
726 pos_array.header.stamp =
header.stamp;
727 pos_array.header.frame_id =
header.frame_id;
728 pos_array.people =
result_.face_positions;
729 if (pos_array.people.size() > 0)
734 std::map<std::string, RestampedPositionMeasurement>::iterator it;
735 for (uint ipa = 0; ipa < pos_array.people.size(); ipa++)
737 it =
pos_list_.find(pos_array.people[ipa].object_id);
738 RestampedPositionMeasurement rpm;
739 rpm.pos = pos_array.people[ipa];
740 rpm.restamp = pos_array.people[ipa].header.stamp;
744 pos_list_.insert(std::pair<std::string, RestampedPositionMeasurement>(pos_array.people[ipa].object_id,
747 else if ((pos_array.people[ipa].header.stamp - (*it).second.pos.header.stamp) >
ros::Duration().
fromSec(-1.0))
766 cloud.channels.resize(1);
767 cloud.channels[0].name =
"intensity";
769 for (uint iface = 0; iface < faces_vector.size(); iface++)
771 one_face = &faces_vector[iface];
774 if (one_face->status ==
"good")
776 geometry_msgs::Point32 p;
777 p.x = one_face->center3d.x;
778 p.y = one_face->center3d.y;
779 p.z = one_face->center3d.z;
780 cloud.points.push_back(p);
781 cloud.channels[0].values.push_back(1.0f);
801 ", number with good depth and size: " << ngood);
815 for (uint iface = 0; iface < faces_vector.size(); iface++)
817 one_face = &faces_vector[iface];
822 if (one_face->status ==
"good")
824 color = cv::Scalar(0, 255, 0);
826 else if (one_face->status ==
"unknown")
828 color = cv::Scalar(255, 0, 0);
832 color = cv::Scalar(0, 0, 255);
836 cv::Point(one_face->box2d.x, one_face->box2d.y),
837 cv::Point(one_face->box2d.x + one_face->box2d.width,
838 one_face->box2d.y + one_face->box2d.height),
850 int main(
int argc,
char **argv)