Skip to content

Commit

Permalink
Merge pull request #6 from ipa-rmb/fuerte_dev
Browse files Browse the repository at this point in the history
same updates as for electric_dev: merge with new code from goa-tz, tested for electric and fuerte
  • Loading branch information
ipa-rmb committed Mar 27, 2013
2 parents 211f440 + 747a0c9 commit 520dc58
Show file tree
Hide file tree
Showing 104 changed files with 30,288 additions and 484 deletions.
61 changes: 60 additions & 1 deletion cob_people_detection/CMakeLists.txt
Expand Up @@ -36,6 +36,9 @@ rosbuild_check_for_sse()

rosbuild_add_boost_directories()

find_package(PCL)
message(STATUS "PCL Include dirs: ${PCL_INCLUDE_DIRS}")

#common commands for building c++ executables and libraries
#rosbuild_add_library(${PROJECT_NAME} src/example.cpp)
#target_link_libraries(${PROJECT_NAME} another_library)
Expand Down Expand Up @@ -64,6 +67,51 @@ rosbuild_add_boost_directories()
#add_custom_command(TARGET people_detector POST_BUILD COMMAND mkdir -p ${PROJECT_SOURCE_DIR}/common/files/training_data)



#rosbuild_add_executable(face_normalizer_node
# common/src/face_normalizer.cpp
# ros/src/face_normalizer_node.cpp)
# target_link_libraries(face_normalizer_node virtual_camera)

rosbuild_add_library(virtual_camera
common/src/virtual_camera.cpp)
target_link_libraries(virtual_camera opencv_core )

#-----------------------------------------------------------------------
#-------------------Tests
#-----------------------------------------------------------------------
rosbuild_add_library(subspace_analysis
common/src/subspace_analysis.cpp)
target_link_libraries(subspace_analysis opencv_core opencv_highgui )
rosbuild_link_boost(subspace_analysis system filesystem)

rosbuild_add_executable(face_normalizer_test
common/src/test/fn_test.cpp
)
target_link_libraries(face_normalizer_test face_normalizer virtual_camera )

rosbuild_add_executable(ssa_test
common/src/test/ssa_test.cpp
)
target_link_libraries(ssa_test subspace_analysis face_normalizer opencv_core opencv_highgui )
#target_link_libraries(ssa_test subspace_analysis face_normalizer opencv_core opencv_highgui boost)

#rosbuild_add_executable(xml_test
# common/src/test/xml_test.cpp
# )
#target_link_libraries(xml_test face_normalizer subspace_analysis opencv_core opencv_highgui )

#rosbuild_add_executable(scene_publisher
# ros/src/scene_publisher.cpp
# )
#target_link_libraries(scene_publisher opencv_core opencv_highgui )
#-----------------------------------------------------------------------
#-----------------------------------------------------------------------


#-----------------------------------------------------------------------
#-----------------------------------------------------------------------

rosbuild_add_executable(people_detection_client
ros/src/people_detection_action_client.cpp)

Expand All @@ -81,11 +129,13 @@ rosbuild_add_executable(face_recognizer_node
common/src/abstract_face_recognizer.cpp
common/src/face_recognizer.cpp
ros/src/face_recognizer_node.cpp)
target_link_libraries(face_recognizer_node face_normalizer subspace_analysis)
rosbuild_link_boost(face_recognizer_node filesystem system)
add_custom_command(TARGET face_recognizer_node POST_BUILD COMMAND mkdir -p ${PROJECT_SOURCE_DIR}/common/files/training_data)

rosbuild_add_executable(detection_tracker_node
ros/src/detection_tracker_node.cpp)
ros/src/detection_tracker_node.cpp
common/src/munkres/munkres.cpp)
rosbuild_link_boost(detection_tracker_node signals)

rosbuild_add_executable(people_detection_display_node
Expand All @@ -97,6 +147,7 @@ rosbuild_add_executable(face_capture_node
common/src/face_recognizer.cpp
ros/src/face_capture_node.cpp)
rosbuild_link_boost(face_capture_node filesystem system signals)
target_link_libraries(face_capture_node face_normalizer subspace_analysis)

rosbuild_add_executable(sensor_message_gateway_node
ros/src/sensor_message_gateway_node.cpp
Expand All @@ -105,9 +156,17 @@ rosbuild_link_boost(sensor_message_gateway_node signals)
rosbuild_add_library(sensor_message_gateway_nodelet
ros/src/sensor_message_gateway_node.cpp
ros/src/sensor_message_gateway_nodelet.cpp)
rosbuild_link_boost(sensor_message_gateway_nodelet signals)

rosbuild_add_executable(coordinator_node
ros/src/coordinator_node.cpp)
rosbuild_link_boost(coordinator_node signals)

rosbuild_add_library(face_normalizer
common/src/face_normalizer.cpp)
target_link_libraries(face_normalizer virtual_camera)



# modified openni tracker
#rosbuild_add_executable(openni_tracker ros/src/openni_tracker.cpp
Expand Down
Expand Up @@ -86,6 +86,7 @@ class AbstractFaceRecognizer
/// @param identification_labels Vector of labels of classified faces, both indices correspond with face_coordinates
/// @return Return code
virtual unsigned long recognizeFaces(std::vector<cv::Mat>& color_images, std::vector< std::vector<cv::Rect> >& face_coordinates, std::vector< std::vector<std::string> >& identification_labels);
virtual unsigned long recognizeFaces(std::vector<cv::Mat>& color_images,std::vector<cv::Mat>& depth_images, std::vector< std::vector<cv::Rect> >& face_coordinates, std::vector< std::vector<std::string> >& identification_labels);

/// Trains a model for the recognition of a given set of faces.
/// @param identification_labels_to_train List of labels whose corresponding faces shall be trained.
Expand All @@ -109,6 +110,7 @@ class AbstractFaceRecognizer
/// @param identification_labels Vector of labels of classified faces, indices correspond with bounding boxes in color_face_coordinates
/// @return Return code
virtual unsigned long recognizeFace(cv::Mat& color_image, std::vector<cv::Rect>& face_coordinates, std::vector<std::string>& identification_labels) = 0;
virtual unsigned long recognizeFace(cv::Mat& color_image,cv::Mat& depth_image, std::vector<cv::Rect>& face_coordinates, std::vector<std::string>& identification_labels) = 0;
};

} // end namespace
Expand Down
@@ -0,0 +1,271 @@
#include <opencv/cv.h>
#include <opencv/cvaux.h>
#include <opencv/highgui.h>
#include <opencv/ml.h>

#include <iostream>


#include <cob_people_detection/virtual_camera.h>
#include <boost/lexical_cast.hpp>


using namespace cv;

namespace FACE{
enum TYPE
{
LEFTEYE,
RIGHTEYE,
NOSE,
MOUTH,
};


template <class T>
class FaceFeatures{
public:




T lefteye;
T righteye;
T nose;
T mouth;
FaceFeatures<T>(){};
~FaceFeatures<T>(){};

void sub_offset(int& ox,int& oy)
{
this->lefteye.x-=ox;
this->lefteye.y-=oy;
this->righteye.x-=ox;
this->righteye.y-=oy;
this->mouth.x-=ox;
this->mouth.y-=oy;
this->nose.x-=ox;
this->nose.y-=oy;
}
void add_offset(int& ox,int& oy)
{
this->lefteye.x+=ox;
this->lefteye.y+=oy;
this->righteye.x+=ox;
this->righteye.y+=oy;
this->mouth.x+=ox;
this->mouth.y+=oy;
this->nose.x+=ox;
this->nose.y+=oy;
}

void scale(double scale)
{
lefteye*=scale;
righteye*=scale;
nose*=scale;
mouth*=scale;
}

std::vector<T> as_vector()
{
std::vector<T> vec;
vec.push_back(lefteye);
vec.push_back(righteye);
vec.push_back(nose);
vec.push_back(mouth);
return vec;
};
bool valid()
{
if(std::isnan(lefteye.x)|| std::isnan(lefteye.y)) return false;
if(std::isnan(righteye.x)|| std::isnan(righteye.y)) return false;
if(std::isnan(nose.x)|| std::isnan(nose.y)) return false;
//if(std::isnan(mouth.x)|| std::isnan(mouth.y)) return false;
else return true;
}
void print()
{
std::cout<<"--------------------"<<std::endl;
std::cout<<"lefteye:\n";
std::cout<<lefteye.x<<" , "<<lefteye.y<<" , "<<lefteye.z<<std::endl;
std::cout<<"righteye:\n";
std::cout<<righteye.x<<" , "<<righteye.y<<" , "<<righteye.z<<std::endl;
std::cout<<"nose:\n";
std::cout<<nose.x<<" , "<<nose.y<<" , "<<nose.z<<std::endl;
std::cout<<"mouth:\n";
std::cout<<mouth.x<<" , "<<mouth.y<<" , "<<mouth.y<<std::endl;
std::cout<<"--------------------"<<std::endl;
}
};


};


class FaceNormalizer{

public:
struct FNConfig
{
bool eq_ill;
bool align;
bool resize;
bool cvt2gray;
};

FaceNormalizer();
FaceNormalizer(FNConfig& config);
FaceNormalizer(int i_epoch_ctr,bool i_debug,bool i_record_scene,std::string i_dbg_path);
~FaceNormalizer();

enum TRAFO
{
AFFINE,
PERSPECTIVE,
};




bool normalizeFace( cv::Mat & img,cv::Size& norm_size);
bool normalizeFace( cv::Mat & img,cv::Mat& depth,cv::Size& norm_size);
bool normalizeFace( cv::Mat& RGB, cv::Mat& XYZ, cv::Size& norm_size, cv::Mat& DM);
void set_norm_face(cv::Size& input_size);
bool normalize_geometry(cv::Mat& img,TRAFO model);
void get_transform_affine(cv::Mat& trafo);
void get_transform_perspective(cv::Mat& trafo);
bool features_from_color(cv::Mat& img);
bool detect_feature(cv::Mat& img,cv::Point2f& coords,FACE::TYPE type);
void dyn_norm_face();
void ident_face();

bool normalize_geometry_depth(cv::Mat& img,cv::Mat& depth);
bool features_from_depth(cv::Mat& depth);
//void despeckle(cv::Mat& src,cv::Mat& dst);
void processDM(cv::Mat& dm,cv::Mat& dm_res);

// Methods for radiometric normalization
bool normalize_radiometry(cv::Mat& img);
void extractVChannel(cv::Mat& img,cv::Mat& V);
void subVChannel(cv::Mat& img,cv::Mat& V);
void eqHist(cv::Mat& img);
void dct(cv::Mat& img);
void tan(cv::Mat& img);
void logAbout(cv::Mat& img);

// Debug/Output methods
void dump_features(cv::Mat& img);
void dump_img(cv::Mat& data,std::string name);
void showImg(cv::Mat& img,std::string window_name);
bool save_scene(cv::Mat& depth,cv::Mat& color,std::string path);
bool read_scene(cv::Mat& depth,cv::Mat& color,std::string path);
bool captureScene( cv::Mat& img,cv::Mat& depth);
bool get_feature_correspondences( cv::Mat& img, cv::Mat& depth, std::vector<cv::Point2f>& img_pts,std::vector<cv::Point3f>& obj_pts);
bool face_coordinate_system(FACE::FaceFeatures<cv::Point3f>& feat_world,FACE::FaceFeatures<cv::Point3f>& feat_local);

template <class T>
void despeckle(cv::Mat& src,cv::Mat& dst)
{




if(src.channels()==1)
{
T* lptr=src.ptr<T>(1,0);
T* rptr=src.ptr<T>(1,2);
T* mptr=src.ptr<T>(1,1);
T* uptr=src.ptr<T>(0,1);
T* dptr=src.ptr<T>(2,1);

int normalizer=4;

for(int px=2*src.cols+2;px<(dst.rows*src.cols);++px)
{
if(*mptr==0)
{
normalizer=4;
if(*lptr==0) normalizer-=1;
if(*rptr==0) normalizer-=1;
if(*uptr==0) normalizer-=1;
if(*dptr==0) normalizer-=1;
if(normalizer>1)*mptr=(*lptr + *rptr + *uptr +*dptr)/normalizer;
else *mptr =75;
}
++lptr;
++rptr;
++mptr;
++uptr;
++dptr;
}
}

if(src.channels()==3)
{
cv::Vec<T,3>* lptr=src.ptr<cv::Vec<T,3> >(1,0);
cv::Vec<T,3>* rptr=src.ptr<cv::Vec<T,3> >(1,2);
cv::Vec<T,3>* mptr=src.ptr<cv::Vec<T,3> >(1,1);
cv::Vec<T,3>* uptr=src.ptr<cv::Vec<T,3> >(0,1);
cv::Vec<T,3>* dptr=src.ptr<cv::Vec<T,3> >(2,1);

int normalizer=4;
for(int px=2*src.cols+2;px<(dst.rows*src.cols);++px)
{
if((*mptr)[0]==0)
{
normalizer=4;
if((*lptr)[0]==0) normalizer-=1;
if((*rptr)[0]==0) normalizer-=1;
if((*uptr)[0]==0) normalizer-=1;
if((*dptr)[0]==0) normalizer-=1;
if(normalizer>1)cv::divide((*lptr + *rptr + *uptr +*dptr),normalizer,*mptr);
else *mptr =75;
}
++lptr;
++rptr;
++mptr;
++uptr;
++dptr;
}
}
//cv::medianBlur(dst,dst,3);
}
//---------------------------------------------------------

protected:

void init();
int fail_ctr;
int epoch_ctr;
bool debug_;
bool vis_debug_;

bool record_scene;
std::string debug_path_;
FNConfig config_;

CvHaarClassifierCascade* nose_cascade_;
CvMemStorage* nose_storage_;

CvHaarClassifierCascade* eye_cascade_;
CvMemStorage* eye_storage_;

CvHaarClassifierCascade* eye_l_cascade_;
CvMemStorage* eye_l_storage_;

CvHaarClassifierCascade* eye_r_cascade_;
CvMemStorage* eye_r_storage_;

CvHaarClassifierCascade* mouth_cascade_;
CvMemStorage* mouth_storage_;


FACE::FaceFeatures<cv::Point2f> f_det_img_, f_norm_img_;
FACE::FaceFeatures<cv::Point3f> f_det_xyz_;

cv::Size norm_size_;
cv::Size input_size_;

VirtualCamera kinect;
};

0 comments on commit 520dc58

Please sign in to comment.