48 #include <boost/filesystem.hpp> 49 #include <boost/thread/mutex.hpp> 51 #include <people_msgs/PositionMeasurement.h> 52 #include <people_msgs/PositionMeasurementArray.h> 58 #include <sensor_msgs/CameraInfo.h> 59 #include <sensor_msgs/Image.h> 60 #include <stereo_msgs/DisparityImage.h> 64 #include <sensor_msgs/PointCloud.h> 65 #include <geometry_msgs/Point32.h> 67 #include <opencv/cxcore.hpp> 68 #include <opencv/cv.hpp> 69 #include <opencv/highgui.h> 76 #include <face_detector/FaceDetectorAction.h> 123 <sensor_msgs::Image, stereo_msgs::DisparityImage, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo>
126 <sensor_msgs::Image, stereo_msgs::DisparityImage, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo>
135 <sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo>
138 <sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo>
180 people_msgs::PositionMeasurement
pos;
183 std::map<std::string, RestampedPositionMeasurement>
pos_list_;
201 BIGDIST_M(1000000.0),
203 as_(nh_, name, false),
215 faces_ =
new Faces();
216 double face_size_min_m, face_size_max_m, max_face_z_m, face_sep_dist_m;
222 local_nh.
param(
"classifier_name", name_, std::string(
""));
223 local_nh.
param(
"classifier_filename", haar_filename_, std::string(
""));
224 local_nh.
param(
"classifier_reliability", reliability_, 0.0);
225 local_nh.
param(
"do_display", do_display_,
false);
226 local_nh.
param(
"do_continuous", do_continuous_,
true);
227 local_nh.
param(
"do_publish_faces_of_unknown_size", do_publish_unknown_,
false);
228 local_nh.
param(
"use_depth", use_depth_,
true);
229 local_nh.
param(
"use_external_init", external_init_,
false);
234 local_nh.
param(
"use_rgbd", use_rgbd_,
false);
235 local_nh.
param(
"queue_size", queue_size, 5);
236 local_nh.
param(
"approximate_sync", approx,
false);
241 cv::namedWindow(
"Face detector: Face Detection", CV_WINDOW_AUTOSIZE);
248 face_size_min_m, face_size_max_m, max_face_z_m, face_sep_dist_m);
256 depth_topic_ =
ros::names::clean(camera_ +
"/" + depth_ns_ +
"/" + depth_image_);
257 camera_info_topic_ =
ros::names::clean(camera_ +
"/" + rgb_ns_ +
"/camera_info");
258 depth_info_topic_ =
ros::names::clean(camera_ +
"/" + depth_ns_ +
"/camera_info");
260 ROS_DEBUG(
"camera_topic_: %s", camera_topic_.c_str());
261 ROS_DEBUG(
"depth_topic_: %s", depth_topic_.c_str());
262 ROS_DEBUG(
"camera_info_topic_: %s", camera_info_topic_.c_str());
263 ROS_DEBUG(
"depth_info_topic_: %s", depth_info_topic_.c_str());
265 local_nh.
param(
"fixed_frame", fixed_frame_, std::string(
"camera_rgb_optical_frame"));
270 image_sub_, depth_image_sub_, c1_info_sub_, c2_info_sub_));
272 this, _1, _2, _3, _4));
277 image_sub_, depth_image_sub_, c1_info_sub_, c2_info_sub_));
279 this, _1, _2, _3, _4));
285 face_size_min_m, face_size_max_m, max_face_z_m, face_sep_dist_m);
291 left_camera_info_topic_ =
ros::names::clean(stereo_namespace_ +
"/left/camera_info");
292 right_camera_info_topic_ =
ros::names::clean(stereo_namespace_ +
"/right/camera_info");
294 local_nh.
param(
"fixed_frame", fixed_frame_, stereo_namespace_.append(
"_optical_frame"));
299 image_sub_, disp_image_sub_, c1_info_sub_, c2_info_sub_));
301 this, _1, _2, _3, _4));
306 image_sub_, disp_image_sub_, c1_info_sub_, c2_info_sub_));
308 this, _1, _2, _3, _4));
316 ROS_INFO_STREAM_NAMED(
"face_detector",
"You must subscribe to one of FaceDetector's outbound topics " 317 "or else it will not publish anything.");
320 boost::mutex::scoped_lock lock(connect_mutex_);
323 pos_array_pub_ = nh_.
advertise<people_msgs::PositionMeasurementArray>(
324 "face_detector/people_tracker_measurements_array", 1, pos_pub_connect_cb, pos_pub_connect_cb);
326 cloud_pub_ = nh_.
advertise<sensor_msgs::PointCloud>(
"face_detector/faces_cloud", 0,
327 cloud_pub_connect_cb, cloud_pub_connect_cb);
339 cv_image_out_.release();
343 cv::destroyWindow(
"Face detector: Face Detection");
356 boost::mutex::scoped_lock lock(connect_mutex_);
362 "so it will no longer publish anything.");
371 image_sub_.
subscribe(it_, camera_topic_, 3);
372 depth_image_sub_.
subscribe(it_, depth_topic_, 3);
373 c1_info_sub_.
subscribe(nh_, camera_info_topic_, 3);
374 c2_info_sub_.
subscribe(nh_, depth_info_topic_, 3);
388 "so it will no longer publish anything.");
397 image_sub_.
subscribe(it_, left_topic_, 3);
398 disp_image_sub_.
subscribe(nh_, disparity_topic_, 3);
399 c1_info_sub_.
subscribe(nh_, left_camera_info_topic_, 3);
400 c2_info_sub_.
subscribe(nh_, right_camera_info_topic_, 3);
467 const sensor_msgs::Image::ConstPtr& depth_image,
468 const sensor_msgs::CameraInfo::ConstPtr& c1_info,
469 const sensor_msgs::CameraInfo::ConstPtr& c2_info)
472 if (!do_continuous_ && !as_.
isActive())
476 result_.face_positions.clear();
486 cv::Mat depth_32fc1 = cv_depth_ptr->image;
487 if (depth_image->encoding !=
"32FC1")
489 cv_depth_ptr->image.convertTo(depth_32fc1, CV_32FC1, 0.001);
497 cv_image_out_ = (cv_image_ptr->image).clone();
500 struct timeval timeofday;
501 gettimeofday(&timeofday, NULL);
504 std::vector<Box2D3D> faces_vector = faces_->
detectAllFacesDepth(cv_image_ptr->image, 1.0, depth_32fc1, &cam_model_);
505 gettimeofday(&timeofday, NULL);
522 const stereo_msgs::DisparityImage::ConstPtr& disp_image,
523 const sensor_msgs::CameraInfo::ConstPtr& c1_info,
524 const sensor_msgs::CameraInfo::ConstPtr& c2_info)
527 if (!do_continuous_ && !as_.
isActive())
531 result_.face_positions.clear();
546 cv_image_out_ = (cv_image_ptr->image).clone();
549 struct timeval timeofday;
550 gettimeofday(&timeofday, NULL);
554 cv_disp_ptr->image, &cam_model_);
555 gettimeofday(&timeofday, NULL);
566 bool found_faces =
false;
569 sensor_msgs::PointCloud cloud;
570 cloud.header.stamp = header.stamp;
571 cloud.header.frame_id = header.frame_id;
573 if (faces_vector.size() > 0)
577 std::map<std::string, RestampedPositionMeasurement>::iterator it;
578 it = pos_list_.begin();
579 while (it != pos_list_.end())
584 pos_list_.erase(it++);
594 tf_.
transformPoint(header.frame_id, header.stamp, loc, fixed_frame_, loc);
595 (*it).second.pos.header.stamp = header.stamp;
596 (*it).second.pos.pos.x = loc[0];
597 (*it).second.pos.pos.y = loc[1];
598 (*it).second.pos.pos.z = loc[2];
610 people_msgs::PositionMeasurement
pos;
611 people_msgs::PositionMeasurementArray pos_array;
613 for (uint iface = 0; iface < faces_vector.size(); iface++)
615 one_face = &faces_vector[iface];
617 if (one_face->
status ==
"good" || (one_face->
status ==
"unknown" && do_publish_unknown_))
622 pos.header.stamp = header.stamp;
627 pos.header.frame_id = header.frame_id;
629 pos.initialization = 1;
630 pos.covariance[0] = 0.04;
631 pos.covariance[1] = 0.0;
632 pos.covariance[2] = 0.0;
633 pos.covariance[3] = 0.0;
634 pos.covariance[4] = 0.04;
635 pos.covariance[5] = 0.0;
636 pos.covariance[6] = 0.0;
637 pos.covariance[7] = 0.0;
638 pos.covariance[8] = 0.04;
646 std::map<std::string, RestampedPositionMeasurement>::iterator close_it = pos_list_.end();
647 for (it = pos_list_.begin(); it != pos_list_.end(); it++)
649 dist = pow((*it).second.pos.pos.x - pos.pos.x, 2.0) +
650 pow((*it).second.pos.pos.y - pos.pos.y, 2.0) +
651 pow((*it).second.pos.pos.z - pos.pos.z, 2.0);
652 if (dist <= faces_->face_sep_dist_m_ && dist < mindist)
658 if (close_it != pos_list_.end())
660 pos.object_id = (*close_it).second.pos.object_id;
661 if (mindist < (*close_it).second.dist)
663 (*close_it).second.restamp = header.stamp;
664 (*close_it).second.dist = mindist;
665 (*close_it).second.pos =
pos;
672 pos.object_id =
static_cast<std::ostringstream*
>(&(std::ostringstream() <<
max_id_))->str();
673 ROS_INFO_STREAM_NAMED(
"face_detector",
"Didn't find face to match, starting new ID " << pos.object_id);
675 result_.face_positions.push_back(pos);
679 pos_array.header.stamp = header.stamp;
680 pos_array.header.frame_id = header.frame_id;
681 pos_array.people = result_.face_positions;
682 if (pos_array.people.size() > 0)
684 pos_array_pub_.
publish(pos_array);
687 std::map<std::string, RestampedPositionMeasurement>::iterator it;
688 for (uint ipa = 0; ipa < pos_array.people.size(); ipa++)
690 it = pos_list_.find(pos_array.people[ipa].object_id);
692 rpm.
pos = pos_array.people[ipa];
693 rpm.
restamp = pos_array.people[ipa].header.stamp;
695 if (it == pos_list_.end())
697 pos_list_.insert(std::pair<std::string, RestampedPositionMeasurement>(pos_array.people[ipa].object_id,
700 else if ((pos_array.people[ipa].header.stamp - (*it).second.pos.header.stamp) >
ros::Duration().
fromSec(-1.0))
708 for (it = pos_list_.begin(); it != pos_list_.end(); it++)
719 cloud.channels.resize(1);
720 cloud.channels[0].name =
"intensity";
722 for (uint iface = 0; iface < faces_vector.size(); iface++)
724 one_face = &faces_vector[iface];
727 if (one_face->
status ==
"good")
729 geometry_msgs::Point32 p;
733 cloud.points.push_back(p);
734 cloud.channels[0].values.push_back(1.0
f);
754 ", number with good depth and size: " << ngood);
757 if (!do_continuous_ && found_faces)
768 for (uint iface = 0; iface < faces_vector.size(); iface++)
770 one_face = &faces_vector[iface];
775 if (one_face->
status ==
"good")
777 color = cv::Scalar(0, 255, 0);
779 else if (one_face->
status ==
"unknown")
781 color = cv::Scalar(255, 0, 0);
785 color = cv::Scalar(0, 0, 255);
788 cv::rectangle(cv_image_out_,
789 cv::Point(one_face->
box2d.x, one_face->
box2d.y),
790 cv::Point(one_face->
box2d.x + one_face->
box2d.width,
796 cv::imshow(
"Face detector: Face Detection", cv_image_out_);
803 int main(
int argc,
char **argv)
void initFaceDetectionDepth(uint num_cascades, std::string haar_classifier_filename, double face_size_min_m, double face_size_max_m, double max_face_z_m, double face_sep_dist_m)
Initialize the face detector with images and depth.
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
message_filters::Subscriber< sensor_msgs::CameraInfo > c2_info_sub_
image_transport::SubscriberFilter depth_image_sub_
boost::shared_ptr< const Goal > acceptNewGoal()
void matchAndDisplay(std::vector< Box2D3D > faces_vector, std_msgs::Header header)
image_geometry::StereoCameraModel cam_model_
A structure for holding information about boxes in 2d and 3d.
std::vector< Box2D3D > detectAllFacesDepth(const cv::Mat &image, double threshold, const cv::Mat &depth_image, image_geometry::StereoCameraModel *cam_model)
Detect all faces in an image and depth image.
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
boost::shared_ptr< ApproximateDepthSync > approximate_depth_sync_
static void pointMsgToTF(const geometry_msgs::Point &msg_v, Point &bt_v)
message_filters::Synchronizer< ExactDepthPolicy > ExactDepthSync
void publish(const boost::shared_ptr< M > &message) const
bool fromCameraInfo(const sensor_msgs::CameraInfo &left, const sensor_msgs::CameraInfo &right)
Time & fromNSec(uint64_t t)
boost::shared_ptr< ExactDispSync > exact_disp_sync_
face_detector::FaceDetectorFeedback feedback_
image_transport::ImageTransport it_
std::string resolveName(const std::string &name, bool remap=true) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ROSCPP_DECL const std::string & getName()
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, stereo_msgs::DisparityImage, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo > ApproximateDispPolicy
#define ROS_INFO_STREAM_NAMED(name, args)
ROSCPP_DECL std::string clean(const std::string &name)
face_detector::FaceDetectorResult result_
message_filters::Synchronizer< ApproximateDispPolicy > ApproximateDispSync
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo > ApproximateDepthPolicy
Position message callback.
void setSucceeded(const Result &result=Result(), const std::string &text=std::string(""))
std::string camera_topic_
std::string camera_info_topic_
ROSCPP_DECL void spin(Spinner &spinner)
void imageCBAllDepth(const sensor_msgs::Image::ConstPtr &image, const sensor_msgs::Image::ConstPtr &depth_image, const sensor_msgs::CameraInfo::ConstPtr &c1_info, const sensor_msgs::CameraInfo::ConstPtr &c2_info)
Image callback for synced messages.
FaceDetector(std::string name)
boost::mutex dimage_mutex_
message_filters::Subscriber< sensor_msgs::CameraInfo > c1_info_sub_
ros::Publisher pos_array_pub_
message_filters::sync_policies::ExactTime< sensor_msgs::Image, stereo_msgs::DisparityImage, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo > ExactDispPolicy
void setPreempted(const Result &result=Result(), const std::string &text=std::string(""))
message_filters::Synchronizer< ExactDispPolicy > ExactDispSync
tf::TransformListener tf_
Duration & fromSec(double t)
actionlib::SimpleActionServer< face_detector::FaceDetectorAction > as_
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
std::string disparity_topic_
std::string stereo_namespace_
void registerPreemptCallback(boost::function< void()> cb)
const Subscriber & getSubscriber() const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
int main(int argc, char **argv)
void initFaceDetectionDisparity(uint num_cascades, std::string haar_classifier_filename, double face_size_min_m, double face_size_max_m, double max_face_z_m, double face_sep_dist_m)
Initialize the face detector with images and disparities.
std::string left_camera_info_topic_
std::string right_camera_info_topic_
message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo > ExactDepthPolicy
void subscribe(ImageTransport &it, const std::string &base_topic, uint32_t queue_size, const TransportHints &transport_hints=TransportHints())
std::map< std::string, RestampedPositionMeasurement > pos_list_
uint32_t getNumSubscribers() const
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
boost::shared_ptr< ExactDepthSync > exact_depth_sync_
Contains a list of faces and functions that can be performed on that list. This includes utility task...
boost::mutex limage_mutex_
std::string depth_info_topic_
image_transport::SubscriberFilter image_sub_
boost::shared_ptr< ApproximateDispSync > approximate_disp_sync_
message_filters::Subscriber< stereo_msgs::DisparityImage > disp_image_sub_
void displayFacesOnImage(std::vector< Box2D3D > faces_vector)
void registerGoalCallback(boost::function< void()> cb)
std::string haar_filename_
boost::mutex connect_mutex_
void imageCBAllDisp(const sensor_msgs::Image::ConstPtr &image, const stereo_msgs::DisparityImage::ConstPtr &disp_image, const sensor_msgs::CameraInfo::ConstPtr &c1_info, const sensor_msgs::CameraInfo::ConstPtr &c2_info)
Image callback for synced messages.
ros::Publisher cloud_pub_
message_filters::Synchronizer< ApproximateDepthPolicy > ApproximateDepthSync
void operator()(void const *) const
people_msgs::PositionMeasurement pos
std::vector< Box2D3D > detectAllFacesDisparity(const cv::Mat &image, double threshold, const cv::Mat &disparity_image, image_geometry::StereoCameraModel *cam_model)
Detect all faces in an image and disparity image.