diff --git a/.gitignore b/.gitignore
index 1cb99f71..d12e823a 100644
--- a/.gitignore
+++ b/.gitignore
@@ -51,3 +51,4 @@ matlab_version/experiments_iccv_300w/wild_fit_clnf/
matlab_version/experiments_iccv_300w/wild_fit_dclm/
matlab_version/experiments_JANUS/all_fit_cvpr/
matlab_version/experiments_JANUS/cfss_fit/
+matlab_runners/Feature Point Experiments/out_dclm/
diff --git a/lib/local/LandmarkDetector/LandmarkDetector.vcxproj b/lib/local/LandmarkDetector/LandmarkDetector.vcxproj
index c06eb3c3..311e3147 100644
--- a/lib/local/LandmarkDetector/LandmarkDetector.vcxproj
+++ b/lib/local/LandmarkDetector/LandmarkDetector.vcxproj
@@ -190,6 +190,7 @@ xcopy /I /E /Y /D "$(SolutionDir)lib\3rdParty\OpenCV3.1\classifiers" "$(OutDir)c
Use
Use
+
Use
Use
@@ -248,6 +249,7 @@ xcopy /I /E /Y /D "$(SolutionDir)lib\3rdParty\OpenCV3.1\classifiers" "$(OutDir)c
+
diff --git a/lib/local/LandmarkDetector/LandmarkDetector.vcxproj.filters b/lib/local/LandmarkDetector/LandmarkDetector.vcxproj.filters
index 34c4cdbb..ecb6c358 100644
--- a/lib/local/LandmarkDetector/LandmarkDetector.vcxproj.filters
+++ b/lib/local/LandmarkDetector/LandmarkDetector.vcxproj.filters
@@ -34,6 +34,9 @@
source
+
+ source
+
@@ -72,6 +75,9 @@
headers
+
+ headers
+
diff --git a/lib/local/LandmarkDetector/include/DPN_patch_expert.h b/lib/local/LandmarkDetector/include/DPN_patch_expert.h
new file mode 100644
index 00000000..7f07575c
--- /dev/null
+++ b/lib/local/LandmarkDetector/include/DPN_patch_expert.h
@@ -0,0 +1,107 @@
+///////////////////////////////////////////////////////////////////////////////
+// Copyright (C) 2016, Carnegie Mellon University and University of Cambridge,
+// all rights reserved.
+//
+// THIS SOFTWARE IS PROVIDED “AS IS” FOR ACADEMIC USE ONLY AND ANY EXPRESS
+// OR IMPLIED WARRANTIES WARRANTIES, INCLUDING, BUT NOT LIMITED TO,
+// THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
+// PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDERS OR CONTRIBUTORS
+// BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY.
+// OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
+// HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
+// STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+// POSSIBILITY OF SUCH DAMAGE.
+//
+// Notwithstanding the license granted herein, Licensee acknowledges that certain components
+// of the Software may be covered by so-called “open source” software licenses (“Open Source
+// Components”), which means any software licenses approved as open source licenses by the
+// Open Source Initiative or any substantially similar licenses, including without limitation any
+// license that, as a condition of distribution of the software licensed under such license,
+// requires that the distributor make the software available in source code format. Licensor shall
+// provide a list of Open Source Components for a particular version of the Software upon
+// Licensee’s request. Licensee will comply with the applicable terms of such licenses and to
+// the extent required by the licenses covering Open Source Components, the terms of such
+// licenses will apply in lieu of the terms of this Agreement. To the extent the terms of the
+// licenses applicable to Open Source Components prohibit any of the restrictions in this
+// License Agreement with respect to such Open Source Component, such restrictions will not
+// apply to such Open Source Component. To the extent the terms of the licenses applicable to
+// Open Source Components require Licensor to make an offer to provide source code or
+// related information in connection with the Software, such offer is hereby made. Any request
+// for source code or related information should be directed to cl-face-tracker-distribution@lists.cam.ac.uk
+// Licensee acknowledges receipt of notices for the Open Source Components for the initial
+// delivery of the Software.
+
+// * Any publications arising from the use of this software, including but
+// not limited to academic journal and conference publications, technical
+// reports and manuals, must cite at least one of the following works:
+//
+// OpenFace: an open source facial behavior analysis toolkit
+// Tadas Baltrušaitis, Peter Robinson, and Louis-Philippe Morency
+// in IEEE Winter Conference on Applications of Computer Vision, 2016
+//
+// Rendering of Eyes for Eye-Shape Registration and Gaze Estimation
+// Erroll Wood, Tadas Baltrušaitis, Xucong Zhang, Yusuke Sugano, Peter Robinson, and Andreas Bulling
+// in IEEE International. Conference on Computer Vision (ICCV), 2015
+//
+// Cross-dataset learning and person-speci?c normalisation for automatic Action Unit detection
+// Tadas Baltrušaitis, Marwa Mahmoud, and Peter Robinson
+// in Facial Expression Recognition and Analysis Challenge,
+// IEEE International Conference on Automatic Face and Gesture Recognition, 2015
+//
+// Constrained Local Neural Fields for robust facial landmark detection in the wild.
+// Tadas Baltrušaitis, Peter Robinson, and Louis-Philippe Morency.
+// in IEEE Int. Conference on Computer Vision Workshops, 300 Faces in-the-Wild Challenge, 2013.
+//
+///////////////////////////////////////////////////////////////////////////////
+
+
+#ifndef __DPN_PATCH_EXPERT_h_
+#define __DPN_PATCH_EXPERT_h_
+
+// system includes
+#include
+
+// OpenCV includes
+#include
+
+namespace LandmarkDetector
+{
+ //===========================================================================
+ /**
+ The classes describing the DPN patch experts
+ */
+
+ class DPN_patch_expert {
+ public:
+
+ // Width and height of the patch expert support area
+ int width;
+ int height;
+
+ // Neural weights
+ std::vector> biases;
+
+ // Neural weights
+ std::vector> weights;
+
+ std::vector activation_function;
+
+ // Confidence of the current patch expert (used for NU_RLMS optimisation)
+ double confidence;
+
+ DPN_patch_expert() { ; }
+
+ // A copy constructor
+ DPN_patch_expert(const DPN_patch_expert& other);
+
+ // Reading in the patch expert
+ void Read(std::ifstream &stream);
+
+ // The actual response computation from intensity image
+ void Response(const cv::Mat_ &area_of_interest, cv::Mat_ &response);
+
+ };
+}
+#endif
diff --git a/lib/local/LandmarkDetector/include/Patch_experts.h b/lib/local/LandmarkDetector/include/Patch_experts.h
index f1ab7386..8c4dde10 100644
--- a/lib/local/LandmarkDetector/include/Patch_experts.h
+++ b/lib/local/LandmarkDetector/include/Patch_experts.h
@@ -65,6 +65,7 @@
#include "SVR_patch_expert.h"
#include "CCNF_patch_expert.h"
+#include "DPN_patch_expert.h"
#include "PDM.h"
namespace LandmarkDetector
@@ -90,6 +91,9 @@ public:
// The node connectivity for CCNF experts, at different window sizes and corresponding to separate edge features
vector > > sigma_components;
+ // The collection of DPN patch experts (for intensity images), the experts are laid out scale->view->landmark
+ vector > > dpn_expert_intensity;
+
// The available scales for intensity patch experts
vector patch_scaling;
@@ -119,7 +123,7 @@ public:
inline int nViews(size_t scale = 0) const { return (int)centers[scale].size(); };
// Reading in all of the patch experts
- void Read(vector intensity_svr_expert_locations, vector depth_svr_expert_locations, vector intensity_ccnf_expert_locations);
+ void Read(vector intensity_svr_expert_locations, vector depth_svr_expert_locations, vector intensity_ccnf_expert_locations, vector intensity_dpn_expert_locations);
@@ -127,7 +131,8 @@ public:
private:
void Read_SVR_patch_experts(string expert_location, std::vector& centers, std::vector >& visibility, std::vector >& patches, double& scale);
void Read_CCNF_patch_experts(string patchesFileLocation, std::vector& centers, std::vector >& visibility, std::vector >& patches, double& patchScaling);
-
+ void Read_DPN_patch_experts(string expert_location, std::vector& centers, std::vector >& visibility, std::vector >& patches, double& scale);
+
};
diff --git a/lib/local/LandmarkDetector/model/dpn_general.txt b/lib/local/LandmarkDetector/model/dpn_general.txt
new file mode 100644
index 00000000..75819785
--- /dev/null
+++ b/lib/local/LandmarkDetector/model/dpn_general.txt
@@ -0,0 +1,6 @@
+PDM pdms/In-the-wild_aligned_PDM_68.txt
+Triangulations tris_68.txt
+PatchesDPN patch_experts/dpn_patches_0.25_general.dat
+PatchesDPN patch_experts/dpn_patches_0.35_general.dat
+PatchesDPN patch_experts/dpn_patches_0.50_general.dat
+PatchesDPN patch_experts/dpn_patches_1.00_general.dat
diff --git a/lib/local/LandmarkDetector/model/main_dclm_general.txt b/lib/local/LandmarkDetector/model/main_dclm_general.txt
new file mode 100644
index 00000000..a163512d
--- /dev/null
+++ b/lib/local/LandmarkDetector/model/main_dclm_general.txt
@@ -0,0 +1,5 @@
+LandmarkDetector dpn_general.txt
+LandmarkDetector_part model_eye/main_clnf_synth_left.txt left_eye_28 36 8 37 10 38 12 39 14 40 16 41 18
+LandmarkDetector_part model_eye/main_clnf_synth_right.txt right_eye_28 42 8 43 10 44 12 45 14 46 16 47 18
+FaceDetConversion haarAlign.txt
+DetectionValidator detection_validation/validator_general_68.txt
\ No newline at end of file
diff --git a/lib/local/LandmarkDetector/src/DPN_patch_expert.cpp b/lib/local/LandmarkDetector/src/DPN_patch_expert.cpp
new file mode 100644
index 00000000..9d3cc36b
--- /dev/null
+++ b/lib/local/LandmarkDetector/src/DPN_patch_expert.cpp
@@ -0,0 +1,261 @@
+///////////////////////////////////////////////////////////////////////////////
+// Copyright (C) 2016, Carnegie Mellon University and University of Cambridge,
+// all rights reserved.
+//
+// THIS SOFTWARE IS PROVIDED “AS IS” FOR ACADEMIC USE ONLY AND ANY EXPRESS
+// OR IMPLIED WARRANTIES WARRANTIES, INCLUDING, BUT NOT LIMITED TO,
+// THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
+// PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDERS OR CONTRIBUTORS
+// BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY.
+// OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
+// HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
+// STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+// POSSIBILITY OF SUCH DAMAGE.
+//
+// Notwithstanding the license granted herein, Licensee acknowledges that certain components
+// of the Software may be covered by so-called “open source” software licenses (“Open Source
+// Components”), which means any software licenses approved as open source licenses by the
+// Open Source Initiative or any substantially similar licenses, including without limitation any
+// license that, as a condition of distribution of the software licensed under such license,
+// requires that the distributor make the software available in source code format. Licensor shall
+// provide a list of Open Source Components for a particular version of the Software upon
+// Licensee’s request. Licensee will comply with the applicable terms of such licenses and to
+// the extent required by the licenses covering Open Source Components, the terms of such
+// licenses will apply in lieu of the terms of this Agreement. To the extent the terms of the
+// licenses applicable to Open Source Components prohibit any of the restrictions in this
+// License Agreement with respect to such Open Source Component, such restrictions will not
+// apply to such Open Source Component. To the extent the terms of the licenses applicable to
+// Open Source Components require Licensor to make an offer to provide source code or
+// related information in connection with the Software, such offer is hereby made. Any request
+// for source code or related information should be directed to cl-face-tracker-distribution@lists.cam.ac.uk
+// Licensee acknowledges receipt of notices for the Open Source Components for the initial
+// delivery of the Software.
+
+// * Any publications arising from the use of this software, including but
+// not limited to academic journal and conference publications, technical
+// reports and manuals, must cite at least one of the following works:
+//
+// OpenFace: an open source facial behavior analysis toolkit
+// Tadas Baltrušaitis, Peter Robinson, and Louis-Philippe Morency
+// in IEEE Winter Conference on Applications of Computer Vision, 2016
+//
+// Rendering of Eyes for Eye-Shape Registration and Gaze Estimation
+// Erroll Wood, Tadas Baltrušaitis, Xucong Zhang, Yusuke Sugano, Peter Robinson, and Andreas Bulling
+// in IEEE International. Conference on Computer Vision (ICCV), 2015
+//
+// Cross-dataset learning and person-speci?c normalisation for automatic Action Unit detection
+// Tadas Baltrušaitis, Marwa Mahmoud, and Peter Robinson
+// in Facial Expression Recognition and Analysis Challenge,
+// IEEE International Conference on Automatic Face and Gesture Recognition, 2015
+//
+// Constrained Local Neural Fields for robust facial landmark detection in the wild.
+// Tadas Baltrušaitis, Peter Robinson, and Louis-Philippe Morency.
+// in IEEE Int. Conference on Computer Vision Workshops, 300 Faces in-the-Wild Challenge, 2013.
+//
+///////////////////////////////////////////////////////////////////////////////
+
+#include "stdafx.h"
+
+#include "DPN_patch_expert.h"
+
+// OpenCV includes
+#include
+#include
+
+// Local includes
+#include "LandmarkDetectorUtils.h"
+
+using namespace LandmarkDetector;
+
+// Copy constructor
+DPN_patch_expert::DPN_patch_expert(const DPN_patch_expert& other) : confidence(other.confidence), width(other.width), height(other.height)
+{
+
+ // Copy the layer weights in a deep way
+ for (size_t i = 0; i < weights.size(); ++i)
+ {
+ this->weights.push_back(other.weights[i].clone());
+ this->biases.push_back(other.biases[i].clone());
+ this->activation_function.push_back(other.activation_function[i]);
+ }
+
+}
+
+//===========================================================================
+void DPN_patch_expert::Read(ifstream &stream)
+{
+
+ // Sanity check
+ int read_type;
+
+ stream.read((char*)&read_type, 4);
+ assert(read_type == 6);
+
+ // the number of neurons for this patch
+ int num_layers;
+ stream.read((char*)&width, 4);
+ stream.read((char*)&height, 4);
+ stream.read((char*)&num_layers, 4);
+
+ if (num_layers == 0)
+ {
+ // empty patch due to landmark being invisible at that orientation
+
+ // read an empty int (due to the way things were written out)
+ stream.read((char*)&num_layers, 4);
+ return;
+ }
+
+ activation_function.resize(num_layers);
+ weights.resize(num_layers);
+ biases.resize(num_layers);
+
+ for (int i = 0; i < num_layers; i++)
+ {
+ int neuron_type;
+ stream.read((char*)&neuron_type, 4);
+ activation_function[i] = neuron_type;
+
+ cv::Mat_ bias;
+ LandmarkDetector::ReadMatBin(stream, bias);
+
+ cv::Mat_ weight;
+ LandmarkDetector::ReadMatBin(stream, weight);
+
+ weights[i] = weight;
+ biases[i] = bias;
+ }
+
+ // Read the patch confidence
+ stream.read((char*)&confidence, 8);
+
+}
+
+// Contrast normalize the input for response map computation
+void contrastNorm(const cv::Mat_& input, cv::Mat_& output)
+{
+
+ int num_cols = input.cols;
+
+ int num_rows = input.rows;
+
+ output = input.clone();
+
+ cv::MatConstIterator_ p = input.begin();
+
+ // Compute row wise
+ for (size_t y = 0; y < num_rows; ++y)
+ {
+
+ cv::Scalar mean_s = cv::mean(input(cv::Rect(1,y,num_cols-1, 1)));
+ double mean = mean_s[0];
+
+ p++;
+
+ float sum_sq = 0;
+ for (size_t x = 1; x < num_cols; ++x)
+ {
+ float curr = *p++;
+ sum_sq += (curr - mean) * (curr - mean);
+ }
+
+ float norm = sqrt(sum_sq);
+
+ if (norm == 0)
+ norm = 1;
+
+ for (size_t x = 1; x < num_cols; ++x)
+ {
+ output.at(y, x) = (output.at(y, x) - mean) / norm;
+ }
+
+ }
+
+}
+
+void im2colBias(const cv::Mat_& input, int width, int height, cv::Mat_& output)
+{
+
+ int m = input.rows;
+ int n = input.cols;
+
+ // determine how many blocks there will be with a sliding window of width x height in the input
+ int yB = m - height + 1;
+ int xB = n - width + 1;
+
+ // Allocate the output size
+ if(output.rows != xB*yB && output.cols != width * height + 1)
+ {
+ output = cv::Mat::ones(xB*yB, width * height + 1, CV_32F);
+ }
+
+ // Iterate over the blocks
+ for (int i = 0; i< yB; i++)
+ {
+ for (int j = 0; j< xB; j++)
+ {
+ // here yours is in different order than I first thought:
+ //int rowIdx = j + i*xB; // my intuition how to index the result
+ int rowIdx = i + j*yB;
+
+ for (unsigned int yy = 0; yy < height; ++yy)
+ for (unsigned int xx = 0; xx < width; ++xx)
+ {
+ int colIdx = xx*height + yy;
+ output.at(rowIdx, colIdx + 1) = input.at(i + yy, j + xx);
+ }
+ }
+ }
+}
+
+//===========================================================================
+void DPN_patch_expert::Response(const cv::Mat_ &area_of_interest, cv::Mat_ &response)
+{
+
+ int response_height = area_of_interest.rows - height + 1;
+ int response_width = area_of_interest.cols - width + 1;
+
+ cv::Mat_ input_col;
+ im2colBias(area_of_interest, width, height, input_col);
+
+ // Mean and standard deviation normalization
+ contrastNorm(input_col, response);
+
+ for (size_t layer = 0; layer < activation_function.size(); ++layer)
+ {
+ response = response * weights[layer];
+
+ // TODO bias could be pre-allocated to the window size so that addition could be quicker
+ for (size_t y = 0; y < response.rows; ++y)
+ {
+ response(cv::Rect(0, y, response.cols, 1)) = response(cv::Rect(0, y, response.cols, 1)) + biases[layer];
+ }
+
+ // Perform activation
+
+ if (activation_function[layer] == 0) // Sigmoid
+ {
+ for (cv::MatIterator_ p = response.begin(); p != response.end(); p++)
+ {
+ *p = 1.0 / (1.0 + exp(-(*p)));
+ }
+ }
+ else if(activation_function[layer] == 2)// ReLU
+ {
+ for (cv::MatIterator_ p = response.begin(); p != response.end(); p++)
+ {
+ if (*p < 0)
+ {
+ *p = 0;
+ }
+ }
+ }
+
+ }
+
+ response = response.reshape(1, response_height);
+ response = response.t();
+
+}
diff --git a/lib/local/LandmarkDetector/src/LandmarkDetectorModel.cpp b/lib/local/LandmarkDetector/src/LandmarkDetectorModel.cpp
index 66695849..60fca774 100644
--- a/lib/local/LandmarkDetector/src/LandmarkDetectorModel.cpp
+++ b/lib/local/LandmarkDetector/src/LandmarkDetectorModel.cpp
@@ -269,6 +269,7 @@ void CLNF::Read_CLNF(string clnf_location)
vector intensity_expert_locations;
vector depth_expert_locations;
vector ccnf_expert_locations;
+ vector dpn_expert_locations;
// The other module locations should be defined as relative paths from the main model
boost::filesystem::path root = boost::filesystem::path(clnf_location).parent_path();
@@ -340,10 +341,14 @@ void CLNF::Read_CLNF(string clnf_location)
{
ccnf_expert_locations.push_back(location);
}
- }
+ else if (module.compare("PatchesDPN") == 0)
+ {
+ dpn_expert_locations.push_back(location);
+ }
+ }
// Initialise the patch experts
- patch_experts.Read(intensity_expert_locations, depth_expert_locations, ccnf_expert_locations);
+ patch_experts.Read(intensity_expert_locations, depth_expert_locations, ccnf_expert_locations, dpn_expert_locations);
// Read in a face detector
face_detector_HOG = dlib::get_frontal_face_detector();
@@ -910,7 +915,17 @@ void CLNF::GetWeightMatrix(cv::Mat_& WeightMatrix, int scale, int view_id
for (int p=0; p < n; p++)
{
- if(!patch_experts.ccnf_expert_intensity.empty())
+ if (!patch_experts.dpn_expert_intensity.empty())
+ {
+
+ // for the x dimension
+ WeightMatrix.at(p, p) = WeightMatrix.at(p, p) + patch_experts.dpn_expert_intensity[scale][view_id][p].confidence;
+
+ // for they y dimension
+ WeightMatrix.at(p + n, p + n) = WeightMatrix.at(p, p);
+
+ }
+ else if(!patch_experts.ccnf_expert_intensity.empty())
{
// for the x dimension
diff --git a/lib/local/LandmarkDetector/src/LandmarkDetectorParameters.cpp b/lib/local/LandmarkDetector/src/LandmarkDetectorParameters.cpp
index c0e74a36..73a4a5a8 100644
--- a/lib/local/LandmarkDetector/src/LandmarkDetectorParameters.cpp
+++ b/lib/local/LandmarkDetector/src/LandmarkDetectorParameters.cpp
@@ -248,7 +248,7 @@ void FaceModelParameters::init()
// For first frame use the initialisation
window_sizes_current = window_sizes_init;
- model_location = "model/main_clnf_general.txt";
+ model_location = "model/main_dclm_general.txt";
sigma = 1.5;
reg_factor = 25;
diff --git a/lib/local/LandmarkDetector/src/Patch_experts.cpp b/lib/local/LandmarkDetector/src/Patch_experts.cpp
index c52d9bd6..d1272ac5 100644
--- a/lib/local/LandmarkDetector/src/Patch_experts.cpp
+++ b/lib/local/LandmarkDetector/src/Patch_experts.cpp
@@ -160,6 +160,7 @@ void Patch_experts::Response(vector >& patch_expert_responses, c
bool use_ccnf = !this->ccnf_expert_intensity.empty();
+ bool use_dpn = !this->dpn_expert_intensity.empty();
// If using CCNF patch experts might need to precalculate Sigmas
if(use_ccnf)
@@ -197,31 +198,36 @@ void Patch_experts::Response(vector >& patch_expert_responses, c
#pragma omp parallel for
#endif
tbb::parallel_for(0, (int)n, [&](int i){
- //for(int i = 0; i < n; i++)
+// for(int i = 0; i < n; i++)
{
-
- if(visibilities[scale][view_id].rows == n)
+
+ if (visibilities[scale][view_id].rows == n)
{
- if(visibilities[scale][view_id].at(i,0) != 0)
+ if (visibilities[scale][view_id].at(i, 0) != 0)
{
// Work out how big the area of interest has to be to get a response of window size
int area_of_interest_width;
int area_of_interest_height;
- if(use_ccnf)
+ if (use_dpn)
{
- area_of_interest_width = window_size + ccnf_expert_intensity[scale][view_id][i].width - 1;
- area_of_interest_height = window_size + ccnf_expert_intensity[scale][view_id][i].height - 1;
+ area_of_interest_width = window_size + dpn_expert_intensity[scale][view_id][i].width - 1;
+ area_of_interest_height = window_size + dpn_expert_intensity[scale][view_id][i].height - 1;
+ }
+ else if (use_ccnf)
+ {
+ area_of_interest_width = window_size + ccnf_expert_intensity[scale][view_id][i].width - 1;
+ area_of_interest_height = window_size + ccnf_expert_intensity[scale][view_id][i].height - 1;
}
else
{
- area_of_interest_width = window_size + svr_expert_intensity[scale][view_id][i].width - 1;
+ area_of_interest_width = window_size + svr_expert_intensity[scale][view_id][i].width - 1;
area_of_interest_height = window_size + svr_expert_intensity[scale][view_id][i].height - 1;
}
-
+
// scale and rotate to mean shape to reference frame
- cv::Mat sim = (cv::Mat_(2,3) << a1, -b1, landmark_locations.at(i,0), b1, a1, landmark_locations.at(i+n,0));
+ cv::Mat sim = (cv::Mat_(2, 3) << a1, -b1, landmark_locations.at(i, 0), b1, a1, landmark_locations.at(i + n, 0));
// Extract the region of interest around the current landmark location
cv::Mat_ area_of_interest(area_of_interest_height, area_of_interest_width);
@@ -229,15 +235,19 @@ void Patch_experts::Response(vector >& patch_expert_responses, c
// Using C style openCV as it does what we need
CvMat area_of_interest_o = area_of_interest;
CvMat sim_o = sim;
- IplImage im_o = grayscale_image;
+ IplImage im_o = grayscale_image;
cvGetQuadrangleSubPix(&im_o, &area_of_interest_o, &sim_o);
-
+
// get the correct size response window
patch_expert_responses[i] = cv::Mat_(window_size, window_size);
- // Get intensity response either from the SVR or CCNF patch experts (prefer CCNF)
- if(!ccnf_expert_intensity.empty())
- {
+ // Get intensity response either from the SVR, CCNF, or DPN patch experts (prefer DPN as they are the most accurate so far)
+ if (!dpn_expert_intensity.empty())
+ {
+ dpn_expert_intensity[scale][view_id][i].Response(area_of_interest, patch_expert_responses[i]);
+ }
+ else if (!ccnf_expert_intensity.empty())
+ {
ccnf_expert_intensity[scale][view_id][i].Response(area_of_interest, patch_expert_responses[i]);
}
@@ -245,14 +255,14 @@ void Patch_experts::Response(vector >& patch_expert_responses, c
{
svr_expert_intensity[scale][view_id][i].Response(area_of_interest, patch_expert_responses[i]);
}
-
+
// if we have a corresponding depth patch and it is visible
- if(!svr_expert_depth.empty() && !depth_image.empty() && visibilities[scale][view_id].at(i,0))
+ if (!svr_expert_depth.empty() && !depth_image.empty() && visibilities[scale][view_id].at(i, 0))
{
cv::Mat_ dProb = patch_expert_responses[i].clone();
cv::Mat_ depthWindow(area_of_interest_height, area_of_interest_width);
-
+
CvMat dimg_o = depthWindow;
cv::Mat maskWindow(area_of_interest_height, area_of_interest_width, CV_32F);
@@ -261,19 +271,19 @@ void Patch_experts::Response(vector >& patch_expert_responses, c
IplImage d_o = depth_image;
IplImage m_o = mask;
- cvGetQuadrangleSubPix(&d_o,&dimg_o,&sim_o);
-
- cvGetQuadrangleSubPix(&m_o,&mimg_o,&sim_o);
+ cvGetQuadrangleSubPix(&d_o, &dimg_o, &sim_o);
+
+ cvGetQuadrangleSubPix(&m_o, &mimg_o, &sim_o);
depthWindow.setTo(0, maskWindow < 1);
svr_expert_depth[scale][view_id][i].ResponseDepth(depthWindow, dProb);
-
+
// Sum to one
double sum = cv::sum(patch_expert_responses[i])[0];
// To avoid division by 0 issues
- if(sum == 0)
+ if (sum == 0)
{
sum = 1;
}
@@ -283,7 +293,7 @@ void Patch_experts::Response(vector >& patch_expert_responses, c
// Sum to one
sum = cv::sum(dProb)[0];
// To avoid division by 0 issues
- if(sum == 0)
+ if (sum == 0)
{
sum = 1;
}
@@ -295,6 +305,7 @@ void Patch_experts::Response(vector >& patch_expert_responses, c
}
}
}
+ //}
}
});
@@ -327,7 +338,7 @@ int Patch_experts::GetViewIdx(const cv::Vec6d& params_global, int scale) const
//===========================================================================
-void Patch_experts::Read(vector intensity_svr_expert_locations, vector depth_svr_expert_locations, vector intensity_ccnf_expert_locations)
+void Patch_experts::Read(vector intensity_svr_expert_locations, vector depth_svr_expert_locations, vector intensity_ccnf_expert_locations, vector intensity_dpn_expert_locations)
{
// initialise the SVR intensity patch expert parameters
@@ -365,6 +376,24 @@ void Patch_experts::Read(vector intensity_svr_expert_locations, vector 0)
+ {
+ centers.resize(num_intensity_dpn);
+ visibilities.resize(num_intensity_dpn);
+ patch_scaling.resize(num_intensity_dpn);
+ dpn_expert_intensity.resize(num_intensity_dpn);
+ }
+
+ for (int scale = 0; scale < num_intensity_dpn; ++scale)
+ {
+ string location = intensity_dpn_expert_locations[scale];
+ cout << "Reading the intensity DPN patch experts from: " << location << "....";
+ Read_DPN_patch_experts(location, centers[scale], visibilities[scale], dpn_expert_intensity[scale], patch_scaling[scale]);
+ }
// initialise the SVR depth patch expert parameters
int num_depth_scales = depth_svr_expert_locations.size();
@@ -569,3 +598,56 @@ void Patch_experts::Read_CCNF_patch_experts(string patchesFileLocation, std::vec
}
}
+//======================= Reading the DPN patch experts =========================================//
+void Patch_experts::Read_DPN_patch_experts(string expert_location, std::vector& centers, std::vector >& visibility, std::vector >& patches, double& scale)
+{
+
+ ifstream patchesFile(expert_location.c_str(), ios::in | ios::binary);
+
+ if (patchesFile.is_open())
+ {
+ patchesFile.read((char*)&scale, 8);
+
+ int numberViews;
+ patchesFile.read((char*)&numberViews, 4);
+
+ // read the visibility
+ centers.resize(numberViews);
+ visibility.resize(numberViews);
+
+ patches.resize(numberViews);
+
+ // centers of each view (which view corresponds to which orientation)
+ for (size_t i = 0; i < centers.size(); i++)
+ {
+ cv::Mat center;
+ LandmarkDetector::ReadMatBin(patchesFile, center);
+ center.copyTo(centers[i]);
+ centers[i] = centers[i] * M_PI / 180.0;
+ }
+
+ // the visibility of points for each of the views (which verts are visible at a specific view
+ for (size_t i = 0; i < visibility.size(); i++)
+ {
+ LandmarkDetector::ReadMatBin(patchesFile, visibility[i]);
+ }
+ int numberOfPoints = visibility[0].rows;
+
+ // read the patches themselves
+ for (size_t i = 0; i < patches.size(); i++)
+ {
+ // number of patches for each view
+ patches[i].resize(numberOfPoints);
+ // read in each patch
+ for (int j = 0; j < numberOfPoints; j++)
+ {
+ patches[i][j].Read(patchesFile);
+ }
+ }
+ cout << "Done" << endl;
+ }
+ else
+ {
+ cout << "Can't find/open the patches file" << endl;
+ }
+}
diff --git a/matlab_runners/Feature Point Experiments/run_clm_feature_point_tests_wild.m b/matlab_runners/Feature Point Experiments/run_clm_feature_point_tests_wild.m
index 0587666d..5b6aaf9b 100644
--- a/matlab_runners/Feature Point Experiments/run_clm_feature_point_tests_wild.m
+++ b/matlab_runners/Feature Point Experiments/run_clm_feature_point_tests_wild.m
@@ -9,6 +9,14 @@ else
database_root = 'D:/Dropbox/Dropbox/AAM/test data/';
end
+%% Run using DPN generak model
+out_clnf = [curr_dir '/out_dclm/'];
+if(~exist(out_clnf, 'file'))
+ mkdir(out_clnf);
+end
+
+[err_dclm, err_no_out_dclm] = Run_CLM_fitting_on_images(out_clnf, database_root, 'use_afw', 'use_lfpw', 'use_ibug', 'use_helen', 'verbose', 'model', 'model/main_dclm_general.txt', 'multi_view', 1);
+
%% Run using CLNF in the wild model
out_clnf = [curr_dir '/out_wild_clnf_wild/'];
if(~exist(out_clnf, 'file'))
@@ -46,6 +54,8 @@ save('results/landmark_detections.mat');
f = fopen('results/landmark_detections.txt', 'w');
fprintf(f, 'Type, mean, median\n');
+fprintf(f, 'err dclm: %f, %f\n', mean(err_dclm), median(err_dclm));
+
fprintf(f, 'err clnf: %f, %f\n', mean(err_clnf), median(err_clnf));
fprintf(f, 'err clnf wild: %f, %f\n', mean(err_clnf_wild), median(err_clnf_wild));
diff --git a/matlab_version/experiments_in_the_wild/Script_DCLM_general.m b/matlab_version/experiments_in_the_wild/Script_DCLM_general.m
index a36550f6..3d0e8a1d 100644
--- a/matlab_version/experiments_in_the_wild/Script_DCLM_general.m
+++ b/matlab_version/experiments_in_the_wild/Script_DCLM_general.m
@@ -22,7 +22,7 @@ clmParams = struct;
clmParams.window_size = [25,25; 23,23; 21,21; 21,21];
clmParams.numPatchIters = size(clmParams.window_size,1);
-[patches] = Load_DCLM_Patch_Experts( '../models/general/', 'dccnf_patches_*_general.mat', [], [], clmParams);
+[patches] = Load_DCLM_Patch_Experts( '../models/dpn/', 'dpn_patches_*_general.mat', [], [], clmParams);
%% Fitting the model to the provided image
diff --git a/matlab_version/models/dpn/create_dpn_experts.m b/matlab_version/models/dpn/create_dpn_experts.m
new file mode 100644
index 00000000..e5031634
--- /dev/null
+++ b/matlab_version/models/dpn/create_dpn_experts.m
@@ -0,0 +1,112 @@
+clear;
+load('C:\Users\tbaltrus\Documents\OpenFace\matlab_version\models\general\ccnf_patches_0.25_general.mat', 'centers', 'visiIndex', 'normalisationOptions');
+
+mirrorInds = [1,17;2,16;3,15;4,14;5,13;6,12;7,11;8,10;18,27;19,26;20,25;21,24;22,23;...
+ 32,36;33,35;37,46;38,45;39,44;40,43;41,48;42,47;49,55;50,54;51,53;60,56;59,57;...
+ 61,65;62,64;68,66];
+
+% For mirroring
+frontalView = 1;
+profileViewInds = [2,3,4];
+
+% Grab all related experts and mirror them appropriatelly, just need to
+% mirror the first layer
+
+non_mirrored = mirrorInds(:,1);
+normalisationOptions = rmfield(normalisationOptions, 'ccnf_ratio');
+normalisationOptions.dccnf = true;
+
+n_landmarks = size(visiIndex, 2);
+n_views = size(visiIndex, 1);
+
+patch_experts.correlations = zeros(n_views, n_landmarks);
+patch_experts.rms_errors = zeros(n_views, n_landmarks);
+patch_experts.types = {'reg'};
+patch_experts.patch_experts = cell(n_views, n_landmarks);
+
+scales = {'0.25', '0.35', '0.50', '1.00'};
+
+for s=scales
+
+ for c=1:n_views
+
+ if(c == frontalView || sum(profileViewInds==c)> 0)
+
+ for i=1:n_landmarks
+
+ if(visiIndex(c,i))
+ mirror = false;
+ % Find the relevant file
+ if(c == frontalView)
+ rel_file = sprintf('D:/deep_experts/rmses/MultiGeneral_arch4general_%s_frontal_%d_512.mat', s{1}, i);
+ else
+ rel_file = sprintf('D:/deep_experts/rmses/MultiGeneral_arch4general_%s_profile%d_%d_512.mat', s{1}, c-1, i);
+ end
+ if(exist(rel_file, 'file'))
+ load(rel_file);
+ else
+ rel_id = mirrorInds(mirrorInds(:,2)==i,1);
+ if(isempty(rel_id))
+ rel_id = mirrorInds(mirrorInds(:,1)==i,2);
+ end
+ if(~visiIndex(c, rel_id))
+ break;
+ end
+ if(c == frontalView)
+ rel_file = sprintf('D:/deep_experts/rmses/MultiGeneral_arch4general_%s_frontal_%d_512.mat', s{1}, rel_id);
+ else
+ rel_file = sprintf('D:/deep_experts/rmses/MultiGeneral_arch4general_%s_profile%d_%d_512.mat', s{1}, c-1, rel_id);
+ end
+ mirror = true;
+ load(rel_file);
+ end
+ patch_experts.correlations(c, i) = correlation_2;
+ patch_experts.rms_errors(c, i) = rmse;
+
+ if(~mirror)
+ patch_experts.patch_experts{c, i} = weights;
+ else
+ flips = fliplr(reshape([1:121]', 11, 11));
+ weights_flipped = weights;
+ weights_flipped{1}(2:end,:) = weights{1}(flips+1,:);
+ patch_experts.patch_experts{c,i} = weights_flipped;
+ end
+ end
+
+ end
+ else
+
+ swap_id = find(centers(:,2) == -centers(c,2));
+
+ corr_T = patch_experts.correlations(swap_id,:);
+ % Appending a mirror view instead, based on the profile view
+ corr_T = swap(corr_T, mirrorInds(:,1), mirrorInds(:,2));
+ patch_experts.correlations(c,:) = corr_T;
+
+ rmsT = patch_experts.rms_errors(swap_id,:);
+ rmsT = swap(rmsT, mirrorInds(:,1), mirrorInds(:,2));
+ patch_experts.rms_errors(c,:) = rmsT;
+
+ patchExpertMirror = patch_experts.patch_experts(swap_id,:);
+ patchExpertMirrorT1 = patchExpertMirror(1,mirrorInds(:,1),:);
+ patchExpertMirrorT2 = patchExpertMirror(1,mirrorInds(:,2),:);
+ patchExpertMirror(1,mirrorInds(:,2),:) = patchExpertMirrorT1;
+ patchExpertMirror(1,mirrorInds(:,1),:) = patchExpertMirrorT2;
+
+ % To flip a patch expert it
+ for p=1:size(patchExpertMirror,2)
+ if(visiIndex(c, p))
+ weights = patchExpertMirror{p};
+ flips = fliplr(reshape([1:121]', 11, 11));
+ weights_flipped = weights;
+ weights_flipped{1}(2:end,:) = weights{1}(flips+1,:);
+ patch_experts.patch_experts{c,p} = weights_flipped;
+ end
+ end
+
+ end
+ end
+ trainingScale = str2num(s{1});
+ save(['dpn_patches_', s{1} '_general.mat'], 'trainingScale', 'centers', 'visiIndex', 'patch_experts', 'normalisationOptions');
+ write_patch_expert_bin(['dpn_patches_', s{1} '_general.dat'], trainingScale, centers, visiIndex, patch_experts);
+end
\ No newline at end of file
diff --git a/matlab_version/models/dpn/swap.m b/matlab_version/models/dpn/swap.m
new file mode 100644
index 00000000..b594e9af
--- /dev/null
+++ b/matlab_version/models/dpn/swap.m
@@ -0,0 +1,6 @@
+function arr = swap(arr, ind1, ind2)
+ val1 = arr(ind1);
+ val2 = arr(ind2);
+ arr(ind1) = val2;
+ arr(ind2) = val1;
+end
\ No newline at end of file
diff --git a/matlab_version/models/dpn/writeMatrixBin.m b/matlab_version/models/dpn/writeMatrixBin.m
new file mode 100644
index 00000000..a0fc5c34
--- /dev/null
+++ b/matlab_version/models/dpn/writeMatrixBin.m
@@ -0,0 +1,37 @@
+% for easier readibility write them row by row
+function writeMatrixBin(fileID, M, type)
+
+ % 4 bytes each for the description
+ fwrite(fileID, size(M,1), 'uint');
+ fwrite(fileID, size(M,2), 'uint');
+ fwrite(fileID, type, 'uint');
+
+ % Convert the matrix to OpenCV format (row minor as opposed to column
+ % minor)
+ M = M';
+
+ % type 0 - uint8, 1 - int8, 2 - uint16, 3 - int16, 4 - int, 5 -
+ % float32, 6 - float64
+
+ % Write out the matrix itself
+
+ switch type
+ case 0
+ type = 'uint8';
+ case 1
+ type = 'int8';
+ case 2
+ type = 'uint16';
+ case 3
+ type = 'int16';
+ case 4
+ type = 'int';
+ case 5
+ type = 'float32';
+ case 6
+ type = 'float64';
+ otherwise
+ type = 'float32';
+ end
+ fwrite(fileID, M, type);
+end
\ No newline at end of file
diff --git a/matlab_version/models/dpn/write_patch_expert_bin.m b/matlab_version/models/dpn/write_patch_expert_bin.m
new file mode 100644
index 00000000..86f05577
--- /dev/null
+++ b/matlab_version/models/dpn/write_patch_expert_bin.m
@@ -0,0 +1,73 @@
+function write_patch_expert_bin(location, trainingScale, centers, visiIndex, patch_experts)
+
+ patches_file = fopen(location, 'w');
+
+ [n_views, n_landmarks, ~] = size(patch_experts.correlations);
+
+ % write out the scaling factor as this is what will be used when
+ % fitting on the window
+ fwrite(patches_file, trainingScale, 'float64');
+
+ fwrite(patches_file, n_views, 'int');
+
+ % Write out the information about the view's and centers here
+ for i=1:n_views
+ % this indicates that we're writing a 3x1 double matrix
+ writeMatrixBin(patches_file, centers(i,:)', 6);
+ end
+
+ % Write out the visibilities
+ for i=1:n_views
+ % this indicates that we're writing a 3x1 double matrix
+ writeMatrixBin(patches_file, visiIndex(i,:)', 4);
+ end
+
+ for i=1:n_views
+ for j=1:n_landmarks
+
+ % Write out that we're writing a dpn patch expert of 11x11 support region
+ fwrite(patches_file, 6, 'int');
+ fwrite(patches_file, 11, 'int');
+ fwrite(patches_file, 11, 'int');
+
+ if(~visiIndex(i,j))
+ % Write out that there won't be any neurons for this
+ % landmark
+ fwrite(patches_file, 0, 'int');
+ fwrite(patches_file, 0, 'int');
+ else
+ num_layers = numel(patch_experts.patch_experts{i,j})/2;
+
+ fwrite(patches_file, num_layers, 'int');
+
+ for n=1:num_layers
+
+ % output the actual layer
+
+ % Layer type, bias, weights
+
+ % Type of layer, first two are relu, the final one is a
+ % sigmoid (0 - sigmoid, 1 - tanh_opt, 2 - ReLU)
+ if(n < 3)
+ fwrite(patches_file, 2, 'int');
+ else
+ fwrite(patches_file, 0, 'int');
+ end
+
+ bias = patch_experts.patch_experts{i,j}{n*2};
+
+ weights = patch_experts.patch_experts{i,j}{n*2-1};
+
+ % the actual bias/weight matrix
+ writeMatrixBin(patches_file, bias, 5);
+ writeMatrixBin(patches_file, weights, 5);
+ end
+
+ % finally write out the confidence
+ fwrite(patches_file, patch_experts.correlations(i,j), 'float64');
+
+ end
+ end
+ end
+
+ fclose(patches_file);