Recognizes faces and takes portrait photographs. More...
#include <FaceFind.h>
Public Slots | |
void | AbortButton () |
A button to send a STOP signal to all project stages in case of an error. | |
void | CornerButton () |
A button to teach the robot the drawing canvas boundaries. | |
void | EdgeButton () |
A button to send a portrait image / mask image pair to the CONTOUR DETECTOR program. | |
void | EdgeImageFromFile (const char *filename) |
a file loading function for the edge image | |
void | HeadButton () |
A button to send a signal to the head controller to get to photo taking position. | |
void | Mirror () |
Toggles mirroring of the scanner pointcloud. | |
void | PaintButton () |
A button to send an edge image retrieved from CONTOUR DETECTOR to the PAINTER program. | |
void | PenButton () |
A button to activate the PEN GRIPPER program. | |
void | PhotoFromFile (const char *photo, const char *mask) |
a file loading function for the photo and mask image | |
void | ReceiveMouseEvent (int, int, int) |
Receive the mouse cursor's position from the GUI. | |
Signals | |
void | activateButton (int) |
(De)activates a GUI button | |
void | newCameraImage (QImage) |
Signals that a new stream image is available. | |
void | newMask (QImage) |
Signals that a new mask image is available. | |
void | newPhoto (QImage) |
Signals that a new portrait image is available. | |
void | newStatusMessage (int, QString) |
Signals that another stage wants some info message printed. | |
void | setGUIInfo (QString) |
Signals that a new GUI info message wants to be printed. | |
void | setGUIStatus (QString) |
Signals that a new GUI status message wants to be printed. | |
Public Member Functions | |
void | AdjustLaser (geometry_msgs::Point p) |
adjust laser to scan only the area around a face | |
void | CameraModelCBAll (const sensor_msgs::CameraInfoConstPtr &cam_info) |
callback function for wide_stereo\left camera model update | |
void | Cluster (cv::Mat_< cv::Vec3b > ©, int n_x, int border_x, int inc_x, int n_y, int border_y, int inc_y) |
does the work for FaceFind::MakeMask | |
QImage | cvMat2QImage (const cv::Mat &image, unsigned int idx) |
Create a QImage from image. | |
bool | EdgeImageCBAll (portrait_robot_msgs::alubsc_node_instr::Request &req, portrait_robot_msgs::alubsc_node_instr::Response &res) |
a ServiceServer callback function for the CONTOUR DETECTOR's response image | |
FaceFind () | |
constructor | |
void | FacePosCBAll (const people_msgs::PositionMeasurement::ConstPtr &position) |
callback function for the face position points sent by a running face_detector node | |
void | ImageCBAll (const sensor_msgs::Image::ConstPtr &limage) |
callback function for the wide_stereo\left camera's image stream and face position visualizer | |
void | MakeMask (cv::Mat &maskImage) |
constructs a mask picture for CONTOUR DETECTOR's edge filtering | |
void | ProsilicaCameraModelCBAll (const sensor_msgs::CameraInfoConstPtr &cam_info) |
callback function for prosilica camera model update | |
void | ProsilicaCBAll (const sensor_msgs::Image::ConstPtr &image) |
callback function for the prosilica camera's image stream | |
bool | StatusMessageCBAll (portrait_robot_msgs::alubsc_status_msg::Request &req, portrait_robot_msgs::alubsc_status_msg::Response &res) |
a ServiceServer callback function for intra-project status updates | |
void | TakePhoto (uint index) |
takes a portrait photo | |
void | TurnHead (cv::Point3d facecenter) |
turns the robot's head in a face's direction | |
Public Attributes | |
ros::ServiceClient | contour_detector_client |
command client for CONTOUR DETECTOR | |
ros::ServiceClient | corner_client |
command client for PAINTER stage's canvas setting functionality | |
ros::ServiceClient | laserscanner_client |
laser scanner client | |
ros::ServiceClient | lasertilt_client |
laser scanner tilt action client | |
ros::ServiceClient | painter_client |
command client for PAINTER | |
ros::ServiceClient | pen_gripper_client |
command client for PEN GRIPPER | |
ros::ServiceClient | prosilica_client |
prosilica high-defition camera service client | |
Private Member Functions | |
bool | CheckFaceBox (int x1, int y1, int x2, int y2) |
Check whether the cursor is in a box. | |
void | MirrorPointCloud () |
Mirror the point cloud. | |
void | StartPhoto (uint index) |
Main interaction between user and video stream. | |
Private Attributes | |
int | drawingCorners_ |
counter for corner setting and drawing button | |
cv::Mat | edgeImage_ |
contour image (received from CONTOUR DETECTOR) | |
std::deque< FaceWrapper > | facesQueue_ |
A FaceWrapper list of faces found so far. | |
bool | headBusy_ |
If the head is moved, it should not be moved again until it has stopped. | |
ros::Time | lastCameraImage_ |
used to track the time for the anti-jittering done in FaceFind::ImageCBAll | |
cv::Point | lastMousePosition_ |
Last known mouse position. | |
bool | mirror_ |
bool | mirroredMaskExists_ |
image_geometry::PinholeCameraModel | model_ |
Camera coordinate conversion model for wide_stereo . | |
int | mouseClicked_ |
image_geometry::PinholeCameraModel | prosilicamodel_ |
Camera coordinate conversion model for prosilica . | |
std::vector< cv::Mat > | rgbaBuffer_ |
Image buffer for gui images. | |
cv::Mat | storedImage_ |
received and stored wide_stereo image | |
cv::Mat | storedMaskImage_ |
mask image | |
cv::Mat | storedMirroredMaskImage_ |
mirrored mask image (if mirroring is active) | |
cv::Mat | storedPhoto_ |
portrait image | |
cv::Mat | storedProsilicaImage_ |
received and stored prosilica image |
Recognizes faces and takes portrait photographs.
This can be seen as the project's main stage in that it glues together all four stages. In working his way through the FaceFind GUI, the user will call each stage to do their respective work. The GUI provides an overview over the current program status by displaying info messages sent by all project stages, and allows for aborting the process by sending STOP signals to all stages.
Definition at line 39 of file FaceFind.h.
constructor
Asserts that camera models FaceFind::model_ and FaceFind::prosilicamodel_ are initialized, initializes the FaceFind::facesQueue.
Definition at line 29 of file FaceFind.cpp.
void FaceFind::AbortButton | ( | ) | [slot] |
A button to send a STOP signal to all project stages in case of an error.
Definition at line 400 of file FaceFind.cpp.
void FaceFind::activateButton | ( | int | ) | [signal] |
(De)activates a GUI button
Connected to UserInterface::ActivateButton.
- | (for parameters see UserInterface::ActivateButton) |
void FaceFind::AdjustLaser | ( | geometry_msgs::Point | p | ) |
adjust laser to scan only the area around a face
This function adjusts / starts the robot's tilting laser scanner.
Firstly, the scanner is moved to a neutral position so the reference frame does not move while transforming coordinates.
Secondly, the wide_stereo_optical_frame
coordinates are transformed into the laser_tilt_mount_link
frame.
The laser is then set to sweep an area around the face as close as possible to the portrait's size.
FaceFind::setGUIInfo signals are emitted to keep the user informed about what's happening.
p | the center point of the face (in wide_stereo_optical_frame coordinates) to be scanned |
Definition at line 796 of file FaceFind.cpp.
void FaceFind::CameraModelCBAll | ( | const sensor_msgs::CameraInfoConstPtr & | cam_info | ) |
callback function for wide_stereo\left
camera model update
This function updates the wide_stereo\left
camera model that is kept for point-to-pixel mapping.
cam_info | new camera information sent by the wide_stereo\left camera |
Definition at line 147 of file FaceFind.cpp.
bool FaceFind::CheckFaceBox | ( | int | x1, |
int | y1, | ||
int | x2, | ||
int | y2 | ||
) | [private] |
Check whether the cursor is in a box.
This function is used to determine whether the cursor is inside a boundary rectangle defining a face portrait, so the user may select an identified face by clicking it in the displayed video stream.
x1 | left border of the boundary box |
y1 | upper border of the boundary box |
x2 | right border of the boundary box |
y2 | lower border of the boundary box |
Definition at line 876 of file FaceFind.cpp.
void FaceFind::Cluster | ( | cv::Mat_< cv::Vec3b > & | copy, |
int | n_x, | ||
int | border_x, | ||
int | inc_x, | ||
int | n_y, | ||
int | border_y, | ||
int | inc_y | ||
) |
does the work for FaceFind::MakeMask
Does all the hard work for FaceFind::MakeMask and should not be called elsewhere.
By checking the neighborhood of each mask image pixel, this function attempts to fill the sparse point cloud to cope with minor defects such as missing points or scanlines distorted by the perspective difference between the tilting laser scanner and the camera. It is a naïve implementation.
Definition at line 761 of file FaceFind.cpp.
void FaceFind::CornerButton | ( | ) | [slot] |
A button to teach the robot the drawing canvas boundaries.
Definition at line 282 of file FaceFind.cpp.
QImage FaceFind::cvMat2QImage | ( | const cv::Mat & | image, |
unsigned int | idx | ||
) |
Create a QImage from image.
The QImage stores its data in the rgbaBuffer_ indexed by idx (reused/overwritten each call)
Definition at line 927 of file FaceFind.cpp.
void FaceFind::EdgeButton | ( | ) | [slot] |
A button to send a portrait image / mask image pair to the CONTOUR DETECTOR program.
Definition at line 248 of file FaceFind.cpp.
bool FaceFind::EdgeImageCBAll | ( | portrait_robot_msgs::alubsc_node_instr::Request & | req, |
portrait_robot_msgs::alubsc_node_instr::Response & | res | ||
) |
a ServiceServer
callback function for the CONTOUR DETECTOR's response image
This function gets the edge image computed by the CONTOUR DETECTOR.
A FaceFind::newMask signal is emitted so that this new image is displayed instead of the previously computed portrait's mask.
A FaceFind::activateButton signal is emitted to render the PAINTER button clickable so the user may proceed to the next stage.
Definition at line 197 of file FaceFind.cpp.
void FaceFind::EdgeImageFromFile | ( | const char * | filename | ) | [slot] |
a file loading function for the edge image
This function gets the edge image from the given file
Definition at line 188 of file FaceFind.cpp.
void FaceFind::FacePosCBAll | ( | const people_msgs::PositionMeasurement::ConstPtr & | position | ) |
callback function for the face position points sent by a running face_detector
node
This function gets people_msgs::PositionMeasurement
messages sent by a running face_detector
node. It inserts the positions and time stamps into the FaceFind::facesQueue and does nothing else.
position | a new face position computed by the face_detector . The latter is started with the wide_stereo camera, so the face position is in the wide_stereo_optical_frame . |
Definition at line 141 of file FaceFind.cpp.
void FaceFind::HeadButton | ( | ) | [slot] |
A button to send a signal to the head controller to get to photo taking position.
Definition at line 365 of file FaceFind.cpp.
void FaceFind::ImageCBAll | ( | const sensor_msgs::Image::ConstPtr & | limage | ) |
callback function for the wide_stereo\left
camera's image stream and face position visualizer
This function gets messages from the wide_stereo\left
camera's compressed image stream.
It then proceeds to visualize each face position in the FaceFind::facesQueue that is less than 2 seconds old (FaceWrapper.time) by drawing a black rectangle around it. If a position is too old, it is instead discarded from the FaceFind::facesQueue. When done, FaceFind::ImageCBAll emits a FaceFind::newCameraImage signal.
The newly got image's time stamp is checked; if a more recent image has already been retrieved, the former is discarded. This prevents the displayed video stream from jittering.
limage | compressed image message of the stereo camera |
Definition at line 62 of file FaceFind.cpp.
void FaceFind::MakeMask | ( | cv::Mat & | maskImage | ) |
constructs a mask picture for CONTOUR DETECTOR's edge filtering
This function clusters the sparse pointcloud points into a homogeneous area so the CONTOUR DETECTOR may more easily tell foreground from background.
A larger blobsize (local variable) slows the process down, but might result in better clustering.
maskImage | a white image with sparse black pixels indication the portraited face's shape (computed in FaceFind::TakePhoto, where this function is called) |
Definition at line 710 of file FaceFind.cpp.
void FaceFind::Mirror | ( | ) | [slot] |
Toggles mirroring of the scanner pointcloud.
This function toggles the mirror functionality implemented in FaceFind::MirrorPointCloud and displays the new mask.
Definition at line 881 of file FaceFind.cpp.
void FaceFind::MirrorPointCloud | ( | ) | [private] |
Mirror the point cloud.
If the tilting laser scanner's pointcloud is suboptimal, mirroring the pointcloud might improve the mask image produced. The user chooses whether this option is applied.
Definition at line 903 of file FaceFind.cpp.
void FaceFind::newCameraImage | ( | QImage | ) | [signal] |
Signals that a new stream image is available.
Used to display the wide_stereo
camera's image stream in the GUI. Connected to UserInterface::SetLeftImage.
- | (for parameters see UserInterface::SetLeftImage) |
void FaceFind::newMask | ( | QImage | ) | [signal] |
Signals that a new mask image is available.
Used to display a portrait's mask image or the edge image sent by CONTOUR DETECTOR in the GUI. Connected to UserInterface::SetRightImage.
- | (for parameters see UserInterface::SetRightImage) |
void FaceFind::newPhoto | ( | QImage | ) | [signal] |
Signals that a new portrait image is available.
Used to display a portrait image in the GUI. Connected to UserInterface::SetCenterImage.
- | (for parameters see UserInterface::SetCenterImage) |
void FaceFind::newStatusMessage | ( | int | , |
QString | |||
) | [signal] |
Signals that another stage wants some info message printed.
Connected to UserInterface::UpdateStatusMessage.
- | (for parameters see UserInterface::UpdateStatusMessage) |
void FaceFind::PaintButton | ( | ) | [slot] |
A button to send an edge image retrieved from CONTOUR DETECTOR to the PAINTER program.
Definition at line 335 of file FaceFind.cpp.
void FaceFind::PenButton | ( | ) | [slot] |
A button to activate the PEN GRIPPER program.
Definition at line 236 of file FaceFind.cpp.
void FaceFind::PhotoFromFile | ( | const char * | photo, |
const char * | mask | ||
) | [slot] |
a file loading function for the photo and mask image
This function gets the photo and mask image from the given files
Definition at line 167 of file FaceFind.cpp.
void FaceFind::ProsilicaCameraModelCBAll | ( | const sensor_msgs::CameraInfoConstPtr & | cam_info | ) |
callback function for prosilica
camera model update
This function updates the prosilica
camera model that is kept for point-to-pixel mapping.
cam_info | new camera information sent by the prosilica camera |
Definition at line 153 of file FaceFind.cpp.
void FaceFind::ProsilicaCBAll | ( | const sensor_msgs::Image::ConstPtr & | image | ) |
callback function for the prosilica
camera's image stream
Using a cvBridge
, the retrieved image message is converted into a cv::Mat
and stored for later use (portrait extraction).
image | the compressed image message sent by the prosilica driver |
Definition at line 46 of file FaceFind.cpp.
void FaceFind::ReceiveMouseEvent | ( | int | x, |
int | y, | ||
int | clicked | ||
) | [slot] |
Receive the mouse cursor's position from the GUI.
x | the cursor's x coordinate |
y | the cursor's y coordinate |
clicked | identifies which button is clicked, if any |
Definition at line 870 of file FaceFind.cpp.
void FaceFind::setGUIInfo | ( | QString | ) | [signal] |
Signals that a new GUI info message wants to be printed.
Connected to UserInterface::SetInfo.
- | (for parameters see UserInterface::SetInfo) |
void FaceFind::setGUIStatus | ( | QString | ) | [signal] |
Signals that a new GUI status message wants to be printed.
Connected to UserInterface::SetStatus.
- | (for parameters see UserInterface::SetStatus) |
void FaceFind::StartPhoto | ( | uint | index | ) | [private] |
Main interaction between user and video stream.
This function implements the main interaction between user and video stream.
By left clicking a recognized face's box in the stream, the tilting laser scanner is adjusted to scan the area around it (FaceFind::AdjustLaser) and the robot turns its head so the prosilica
camera can see the face (FaceFind::TurnHead).
By right clicking a recognized face's box in the stream, FaceFind::TakePhoto is called to take a portrait image of that face.
face_detector
), the prosilica
high-definition camera used for the actual portrait image has a much narrower field of view so it might not see the face. index | the clicked face's index in the FaceFind::facesQueue |
Definition at line 419 of file FaceFind.cpp.
bool FaceFind::StatusMessageCBAll | ( | portrait_robot_msgs::alubsc_status_msg::Request & | req, |
portrait_robot_msgs::alubsc_status_msg::Response & | res | ||
) |
a ServiceServer
callback function for intra-project status updates
This function gets the status update a project part wants to be printed and emits a FaceFind::newStatusMessage signal.
It does not use the service call's response part.
Definition at line 159 of file FaceFind.cpp.
void FaceFind::TakePhoto | ( | uint | index | ) |
takes a portrait photo
This function implements the face finder's main functionality: It takes a face position, extracts a portrait image from it and computes a mask separating the face from the image background.
A face position is fetched from the FaceFind::facesQueue and transformed from wide_stereo_optical_frame
to high_def_optical_frame
. A laser_assembler is then used to compile the tilting scanner's scanlines from up to 5 seconds in the past into a single pointcloud. Its frame is base_link
, so it, too, is transformed into the high_def_optical_frame
.
The portrait area is then cut from the image and a mask image of the same size is created. The pointcloud's points that can be mapped onto the face are then visualized as pixels in the mask (whether a point belongs to the face is determined by looking at its distance from the camera: If it differs too strongly from the face center's distance, it is classified as background and thus not marked).
Resized versions of the two resulting images are displayed in the GUI, where a button to proceed to the CONTOUR DETECTOR stage is enabled. Unresized versions of the images are kept to be sent to this next stage.
Throughout the process, FaceFind::setGUIStatus and FaceFind::setGUIInfo signals are emitted to keep the user informed
index | the FaceFind::facesQueue index of the face whose portrait is to be taken |
Definition at line 459 of file FaceFind.cpp.
void FaceFind::TurnHead | ( | cv::Point3d | facecenter | ) |
turns the robot's head in a face's direction
This function gets a face position in wide_stereo_optical_frame
coordinates (the wide_stereo
camera's frame).
It converts these coordinates to the prosilica
camera's frame (high_def_optical_frame
), which is sent to an actionlib::SimpleActionClient<pr2_controllers_msgs::PointHeadAction>
on /head_traj_controller/point_head_action
, so afterwards the face is in the center of the prosilica
high-definition camera image from which portraits are extracted.
Source: http://www.ros.org/wiki/pr2_controllers/Tutorials/Moving%20the%20Head
facecenter | the point the head should turn to face, given in the wide_stereo_optical_frame |
Definition at line 673 of file FaceFind.cpp.
command client for CONTOUR DETECTOR
Definition at line 147 of file FaceFind.h.
command client for PAINTER stage's canvas setting functionality
Definition at line 149 of file FaceFind.h.
int FaceFind::drawingCorners_ [private] |
counter for corner setting and drawing button
Definition at line 373 of file FaceFind.h.
cv::Mat FaceFind::edgeImage_ [private] |
contour image (received from CONTOUR DETECTOR)
Definition at line 311 of file FaceFind.h.
std::deque<FaceWrapper> FaceFind::facesQueue_ [private] |
A FaceWrapper list of faces found so far.
Definition at line 314 of file FaceFind.h.
bool FaceFind::headBusy_ [private] |
If the head is moved, it should not be moved again until it has stopped.
Definition at line 370 of file FaceFind.h.
laser scanner client
Definition at line 140 of file FaceFind.h.
laser scanner tilt action client
Definition at line 143 of file FaceFind.h.
ros::Time FaceFind::lastCameraImage_ [private] |
used to track the time for the anti-jittering done in FaceFind::ImageCBAll
Definition at line 376 of file FaceFind.h.
cv::Point FaceFind::lastMousePosition_ [private] |
Last known mouse position.
Definition at line 326 of file FaceFind.h.
bool FaceFind::mirror_ [private] |
Definition at line 366 of file FaceFind.h.
bool FaceFind::mirroredMaskExists_ [private] |
Definition at line 367 of file FaceFind.h.
image_geometry::PinholeCameraModel FaceFind::model_ [private] |
Camera coordinate conversion model for wide_stereo
.
Definition at line 317 of file FaceFind.h.
int FaceFind::mouseClicked_ [private] |
Definition at line 327 of file FaceFind.h.
command client for PAINTER
Definition at line 148 of file FaceFind.h.
command client for PEN GRIPPER
Definition at line 146 of file FaceFind.h.
prosilica
high-defition camera service client
Definition at line 137 of file FaceFind.h.
image_geometry::PinholeCameraModel FaceFind::prosilicamodel_ [private] |
Camera coordinate conversion model for prosilica
.
Definition at line 320 of file FaceFind.h.
std::vector<cv::Mat> FaceFind::rgbaBuffer_ [private] |
Image buffer for gui images.
Definition at line 323 of file FaceFind.h.
cv::Mat FaceFind::storedImage_ [private] |
received and stored wide_stereo
image
Definition at line 301 of file FaceFind.h.
cv::Mat FaceFind::storedMaskImage_ [private] |
mask image
Definition at line 307 of file FaceFind.h.
cv::Mat FaceFind::storedMirroredMaskImage_ [private] |
mirrored mask image (if mirroring is active)
Definition at line 309 of file FaceFind.h.
cv::Mat FaceFind::storedPhoto_ [private] |
portrait image
Definition at line 305 of file FaceFind.h.
cv::Mat FaceFind::storedProsilicaImage_ [private] |
received and stored prosilica
image
Definition at line 303 of file FaceFind.h.