Skip to content

Commit

Permalink
[kinetic] Package Cleanup (#89)
Browse files Browse the repository at this point in the history
  • Loading branch information
DLu authored Jan 19, 2021
1 parent 213bac2 commit bda9391
Show file tree
Hide file tree
Showing 54 changed files with 1,916 additions and 2,117 deletions.
42 changes: 25 additions & 17 deletions face_detector/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -25,13 +25,6 @@ find_package(catkin REQUIRED COMPONENTS
find_package(Boost REQUIRED COMPONENTS signals system thread)
find_package(OpenCV)

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

add_action_files(
DIRECTORY action
FILES FaceDetector.action
Expand Down Expand Up @@ -59,33 +52,44 @@ catkin_package(
tf
)

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

add_executable(face_detector
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
${catkin_LIBRARIES}
${Boost_LIBRARIES}
${OpenCV_LIBRARIES})

add_dependencies(face_detector ${catkin_EXPORTED_TARGETS} ${${PROJECT_NAME}_EXPORTED_TARGETS})

install(TARGETS
face_detector
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
install(TARGETS face_detector
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)

install(DIRECTORY include/face_detector/
install(DIRECTORY include/${PROJECT_NAME}/
DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
)

install(DIRECTORY launch param
install(DIRECTORY param
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/
)
install(DIRECTORY launch
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 @@ -107,4 +111,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()
53 changes: 20 additions & 33 deletions face_detector/include/face_detector/faces.h
Original file line number Diff line number Diff line change
Expand Up @@ -38,36 +38,31 @@

/* Author: Caroline Pantofaru */

#ifndef FACES_H
#define FACES_H


#ifndef FACE_DETECTOR_FACES_H
#define FACE_DETECTOR_FACES_H

#include <string>
#include <vector>

#include <opencv/cv.hpp>
#include <opencv/cxcore.hpp>
#include <opencv/cvaux.hpp>

#include "image_geometry/stereo_camera_model.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 @@ -78,30 +73,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 @@ -111,15 +102,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 @@ -132,7 +120,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 @@ -146,7 +135,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 @@ -156,8 +146,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 @@ -167,13 +157,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 @@ -192,10 +182,7 @@ class Faces

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

};

};
} // namespace people

#endif

#endif // FACE_DETECTOR_FACES_H
8 changes: 5 additions & 3 deletions face_detector/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@
<depend>geometry_msgs</depend>
<depend>image_geometry</depend>
<depend>image_transport</depend>
<depend>message_filters</depend>
<depend>people_msgs</depend>
<depend>rosbag</depend>
<depend>roscpp</depend>
Expand All @@ -25,17 +26,18 @@
<depend>sensor_msgs</depend>
<depend>std_msgs</depend>
<depend>std_srvs</depend>
<depend>stereo_image_proc</depend>
<depend>stereo_msgs</depend>
<depend>tf</depend>
<depend>message_filters</depend>
<depend>stereo_image_proc</depend>

<build_depend>message_generation</build_depend>
<build_export_depend>message_runtime</build_export_depend>

<exec_depend>dynamic_reconfigure</exec_depend>
<exec_depend>message_runtime</exec_depend>

<test_depend>stereo_image_proc</test_depend>
<test_depend>roslaunch</test_depend>
<test_depend>roslint</test_depend>
<test_depend>rostest</test_depend>
<test_depend>stereo_image_proc</test_depend>
</package>
25 changes: 11 additions & 14 deletions face_detector/scripts/face_detector_action_client.py
Original file line number Diff line number Diff line change
@@ -1,41 +1,38 @@
#! /usr/bin/env python

import roslib; roslib.load_manifest('face_detector')
import rospy

# Brings in the SimpleActionClient
import actionlib

# Brings in the messages used by the face_detector action, including the
# goal message and the result message.
import face_detector.msg
from face_detector.msg import FaceDetectorAction, FaceDetectorGoal

import rospy


def face_detector_client():
# Creates the SimpleActionClient, passing the type of the action to the constructor.
client = actionlib.SimpleActionClient('face_detector_action', face_detector.msg.FaceDetectorAction)
client = actionlib.SimpleActionClient('face_detector_action', FaceDetectorAction)

# Waits until the action server has started up and started
# listening for goals.
client.wait_for_server()

# Creates a goal to send to the action server.
goal = face_detector.msg.FaceDetectorGoal()
# Creates a goal to send to the action server. (no parameters)
goal = FaceDetectorGoal()

# Sends the goal to the action server.
client.send_goal(goal)

# Waits for the server to finish performing the action.
client.wait_for_result()

# Prints out the result of executing the action
return client.get_result() # A FibonacciResult
return client.get_result() # people_msgs/PositionMeasurement[] face_positions


if __name__ == '__main__':
try:
# Initializes a rospy node so that the SimpleActionClient can
# publish and subscribe over ROS.
rospy.init_node('face_detector_action_client')
result = face_detector_client()
print "Done action"
print('Done action')
except rospy.ROSInterruptException:
print "Program interrupted before completion"
print('Program interrupted before completion')
Loading

0 comments on commit bda9391

Please sign in to comment.