Skip to content

Commit

Permalink
based on upstream/noetic
Browse files Browse the repository at this point in the history
  • Loading branch information
LeroyR committed Sep 22, 2022
1 parent 6d689fb commit 1af2993
Show file tree
Hide file tree
Showing 87 changed files with 2,361 additions and 2,586 deletions.
20 changes: 20 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
People
======
Algorithms related to detecting and tracking people using various robot sensors.

## Documentation
[http://ros.org/wiki/people](http://ros.org/wiki/people)

## Status
| Distro | Status |
| ------ | ------ |
| **Kinetic** | [![Kinetic Build Status](http://build.ros.org/buildStatus/icon?job=Kbin_uX64__people__ubuntu_xenial_amd64__binary)](http://build.ros.org/job/Kbin_uX64__people__ubuntu_xenial_amd64__binary/) |
| **Melodic** | [![Melodic Build Status](http://build.ros.org/buildStatus/icon?job=Mbin_uB64__people__ubuntu_bionic_amd64__binary)](http://build.ros.org/job/Mbin_uB64__people__ubuntu_bionic_amd64__binary/) |
| **Dashing** | None |

## Current Branches
* `kinetic` is used by the ROS `kinetic` distro.

* `melodic` is used by the ROS `melodic` distro.

* `ros2` is used by the ROS2 `dashing` distro.
6 changes: 6 additions & 0 deletions face_detector/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,12 @@
Changelog for package face_detector
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

1.2.0 (2019-08-19)
------------------
* Whitespace cleanu (`#73 <https://github.com/wg-perception/people/issues/73>`_)
* Remove and move unused includes (`#70 <https://github.com/wg-perception/people/issues/70>`_)
* Contributors: David V. Lu!!, Shane Loretz

1.0.9 (2015-09-01)
------------------
* Install missing param directory: face_detector.rgbd.launch fails due to the `param` folder.
Expand Down
118 changes: 71 additions & 47 deletions face_detector/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,77 +1,97 @@
cmake_minimum_required(VERSION 2.8.3)
cmake_minimum_required(VERSION 3.0.2)
project(face_detector)

find_package(catkin REQUIRED COMPONENTS
roscpp
std_msgs
geometry_msgs
std_srvs
cv_bridge
stereo_msgs
sensor_msgs
tf
rosbag
image_transport
people_msgs
image_geometry
actionlib
actionlib_msgs
message_generation
rospy
roslib)
actionlib
actionlib_msgs
cv_bridge
geometry_msgs
image_geometry
image_transport
message_filters
message_generation
people_msgs
rosbag
roscpp
roslib
rospy
sensor_msgs
std_msgs
std_srvs
stereo_msgs
tf
)

find_package(Boost REQUIRED COMPONENTS signals system thread)
find_package(Boost REQUIRED COMPONENTS system thread)
find_package(OpenCV)

include_directories(
include
${Boost_INCLUDE_DIRS}
${OpenCV_INCLUDE_DIRS}
${catkin_INCLUDE_DIRS})
find_package(yaml-cpp REQUIRED)

add_action_files(
DIRECTORY action
FILES FaceDetector.action
)
generate_messages(DEPENDENCIES actionlib_msgs people_msgs)

catkin_package(INCLUDE_DIRS include
CATKIN_DEPENDS people_msgs
geometry_msgs
actionlib_msgs
stereo_msgs
sensor_msgs
std_msgs
message_runtime)
catkin_package(
INCLUDE_DIRS include
CATKIN_DEPENDS
actionlib
actionlib_msgs
cv_bridge
geometry_msgs
image_geometry
image_transport
message_filters
message_runtime
people_msgs
roscpp
roslib
rospy
sensor_msgs
std_msgs
stereo_msgs
tf
)

include_directories(
include
${Boost_INCLUDE_DIRS}
${OpenCV_INCLUDE_DIRS}
${catkin_INCLUDE_DIRS}
)

add_executable(face_detector
src/face_detection.cpp
src/face_detection.cpp
src/faces.cpp)
target_link_libraries(${PROJECT_NAME}
add_dependencies(face_detector ${catkin_EXPORTED_TARGETS} ${${PROJECT_NAME}_EXPORTED_TARGETS})
target_link_libraries(face_detector
yaml-cpp
${catkin_LIBRARIES}
${Boost_LIBRARIES}
${OpenCV_LIBRARIES})

add_dependencies(face_detector ${PROJECT_NAME}_generate_messages_cpp)


install(TARGETS
face_detector
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
install(TARGETS face_detector
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)
install(DIRECTORY include/${PROJECT_NAME}/
DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
)

install(DIRECTORY include/face_detector/
DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
install(DIRECTORY param
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/
)
install(DIRECTORY launch
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/
)

install(DIRECTORY launch param
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/
catkin_install_python(PROGRAMS scripts/face_detector_action_client.py
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)

if(CATKIN_ENABLE_TESTING)
find_package(rostest REQUIRED)
find_package(roslint REQUIRED)
find_package(roslaunch REQUIRED)

catkin_download_test_data(${PROJECT_NAME}_noface_test_diamondback.bag
http://download.ros.org/data/face_detector/face_detector_noface_test_diamondback.bag
Expand All @@ -93,4 +113,8 @@ if(CATKIN_ENABLE_TESTING)
# add_rostest(test/action-rgbd_true_rtest.xml)
# add_rostest(test/action-rgbd_false_rtest.xml)

roslint_cpp()
roslaunch_add_file_check(launch)
roslint_python()
roslint_add_test()
endif()
8 changes: 8 additions & 0 deletions face_detector/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
# face_detector

See [the ROS wiki](http://wiki.ros.org/face_detector) for full information.

## Note about classifier files
The package is a ROS wrapper around OpenCV's face detection algorithm. You need to provide a classifier configuration file for it to work, specified as the `classifier_filename` ROS parameter.

Older versions of this package would only accept an absolute path. Now, if the configuration file is not found using the absolute path, it will use check the list of default folders. This can be provided using the `classifier_folders` ROS parameter, or if that is not set, will use the values in `param/default_folders.yaml`.
62 changes: 22 additions & 40 deletions face_detector/include/face_detector/faces.h
Original file line number Diff line number Diff line change
Expand Up @@ -38,40 +38,30 @@

/* Author: Caroline Pantofaru */

#ifndef FACES_H
#define FACES_H
#ifndef FACE_DETECTOR_FACES_H
#define FACE_DETECTOR_FACES_H



#include <stdio.h>
#include <iostream>
#include <string>
#include <vector>

#include <opencv/cv.hpp>
#include <opencv/cxcore.hpp>
#include <opencv/cvaux.hpp>
#include <opencv2/core/core_c.h>
#include <opencv2/objdetect.hpp>

#include "image_geometry/stereo_camera_model.h"
#include "ros/time.h"
#include <ros/console.h>
#include <image_geometry/stereo_camera_model.h>
#include <boost/thread/mutex.hpp>
#include <boost/bind.hpp>
#include <boost/thread/thread.hpp>
#include <boost/thread/condition.hpp>


using namespace std;

#define FACE_SIZE_MIN_M 0.1 /**< Default minimum face size, in meters. Only use this for initialization. */
#define FACE_SIZE_MAX_M 0.5 /**< Default maximum face size, in meters. Only use this for initialization. */
#define MAX_FACE_Z_M 8.0 /**< Default maximum distance from the camera, in meters. Only use this for initialization. */
#define MAX_FACE_Z_M 8.0 /**< Default maximum distance from the camera, in meters. Only use for initialization. */
// Default thresholds for face tracking.
#define FACE_SEP_DIST_M 1.0 /**< Default separation distance for associating faces. Only use this for initialization. */

namespace people
{


/*!
* \brief A structure for holding information about boxes in 2d and 3d.
*/
Expand All @@ -82,30 +72,26 @@ struct Box2D3D
double width2d;
double width3d;
cv::Rect box2d;
string status;
std::string status;
int id;
};


/*!
* \brief A structure containing the person's identifying data.
*/
struct Face
{
string id;
string name;
std::string id;
std::string name;
};


/*!
* \brief Contains a list of faces and functions that can be performed on that list.
* This includes utility tasks such as set/get data, to more complicated tasks such as detection or tracking.
*/

class Faces
{
public:

// Default thresholds for the face detection algorithm.

// Thresholds for the face detection algorithm.
Expand All @@ -115,15 +101,12 @@ class Faces
// Thresholds for face tracking.
double face_sep_dist_m_; /**< Separation distance for associating faces. */



// Create an empty list of people.
Faces();

// Destroy a list of people.
~Faces();


/*!
* \brief Detect all faces in an image and disparity image.
*
Expand All @@ -136,7 +119,8 @@ class Faces
* Output:
* A vector of Box2D3Ds containing the bounding boxes around found faces in 2D and 3D.
*/
vector<Box2D3D> detectAllFacesDisparity(const cv::Mat &image, double threshold, const cv::Mat &disparity_image, image_geometry::StereoCameraModel *cam_model);
std::vector<Box2D3D> detectAllFacesDisparity(const cv::Mat &image, double threshold, const cv::Mat &disparity_image,
image_geometry::StereoCameraModel *cam_model);

/*!
* \brief Detect all faces in an image and depth image.
Expand All @@ -150,7 +134,8 @@ class Faces
* Output:
* A vector of Box2D3Ds containing the bounding boxes around found faces in 2D and 3D.
*/
vector<Box2D3D> detectAllFacesDepth(const cv::Mat &image, double threshold, const cv::Mat &depth_image, image_geometry::StereoCameraModel *cam_model);
std::vector<Box2D3D> detectAllFacesDepth(const cv::Mat &image, double threshold, const cv::Mat &depth_image,
image_geometry::StereoCameraModel *cam_model);

/*!
* \brief Initialize the face detector with images and disparities.
Expand All @@ -160,8 +145,8 @@ class Faces
* \param num_cascades Should always be 1 (may change in the future.)
* \param haar_classifier_filename Full path to the cascade file.
*/
void initFaceDetectionDisparity(uint num_cascades, string haar_classifier_filename, double face_size_min_m, double face_size_max_m, double max_face_z_m, double face_sep_dist_m);

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);

/*!
* \brief Initialize the face detector with images and depth.
Expand All @@ -171,13 +156,13 @@ class Faces
* \param num_cascades Should always be 1 (may change in the future.)
* \param haar_classifier_filename Full path to the cascade file.
*/
void initFaceDetectionDepth(uint num_cascades, string haar_classifier_filename, double face_size_min_m, double face_size_max_m, double max_face_z_m, double face_sep_dist_m);
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);

////////////////////
private:

vector<Face> list_; /**< The list of face ids. */
vector<Box2D3D> faces_; /**< The list of face positions. */
std::vector<Face> list_; /**< The list of face ids. */
std::vector<Box2D3D> faces_; /**< The list of face positions. */

cv::Mat cv_image_gray_; /**< Grayscale image */
cv::Mat const* disparity_image_; /**< Disparity image */
Expand All @@ -196,10 +181,7 @@ class Faces

void faceDetectionThreadDisparity(uint i);
void faceDetectionThreadDepth(uint i);

};

};
} // namespace people

#endif

#endif // FACE_DETECTOR_FACES_H
11 changes: 5 additions & 6 deletions face_detector/launch/face_detector.rgbd.launch
Original file line number Diff line number Diff line change
@@ -1,20 +1,19 @@
<launch>

<!-- Following args `camera` and `depth_ns` together consist the namespace prefix, and the args `*_topic` make the body of the topic for face_detector node to subscribe. In the example below, you're subscribing to:
<!-- Following args `camera` and `depth_ns` together consist the namespace prefix, and the args `*_topic` make the body of the topic for face_detector node to subscribe. In the example below, you're subscribing to:
/camera/rgb/image_rect_color
/camera/depth_ns/image_rect_raw
/camera/depth_ns/image_rect_raw
-->
<arg name="camera" default="camera" />
<arg name="rgb_ns" default="rgb" />
<arg name="rgb_ns" default="rgb" />
<arg name="depth_ns" default="depth_registered" />
<arg name="image_topic" default="image_rect_color" />
<arg name="depth_topic" default="image_rect_raw" />
<arg name="fixed_frame" default="camera_rgb_optical_frame" />

<arg name="paramfile_classifier" default="$(find face_detector)/param/classifier.yaml"/>

<!--include file="$(find openni_launch)/launch/openni.launch"/-->
<node name="$(anon dynparam)" pkg="dynamic_reconfigure" type="dynparam" args="set_from_parameters $(arg camera)/driver">
<param name="depth_registration" type="bool" value="true" />
</node>
Expand All @@ -23,15 +22,15 @@
<arg name="camera" value="$(arg camera)" />
<arg name="rgb_ns" value="$(arg rgb_ns)" />
<arg name="image_topic" value="$(arg image_topic)" />
<arg name="depth_topic" value="$(arg depth_topic)" />
<arg name="depth_topic" value="$(arg depth_topic)" />
<arg name="depth_ns" value="$(arg depth_ns)" />
<arg name="fixed_frame" value="$(arg fixed_frame)" />

<arg name="classifier_name" value="frontalface" />
<arg name="paramfile_classifier" value="$(arg paramfile_classifier)"/>
<arg name="classifier_reliability" value="0.9"/>
<arg name="do_continuous" value="true" />
<arg name="do_publish_faces_of_unknown_size" value="false" />
<arg name="do_publish_faces_of_unknown_size" value="false" />
<arg name="do_display" value="false" />
<arg name="use_rgbd" value="true" />
<arg name="approximate_sync" value="true" />
Expand Down
Loading

0 comments on commit 1af2993

Please sign in to comment.