BlurrinessMetric.cpp
Go to the documentation of this file.
1 /*
2  * This file is part of ArmarX.
3  *
4  * ArmarX is free software; you can redistribute it and/or modify
5  * it under the terms of the GNU General Public License version 2 as
6  * published by the Free Software Foundation.
7  *
8  * ArmarX is distributed in the hope that it will be useful, but
9  * WITHOUT ANY WARRANTY; without even the implied warranty of
10  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
11  * GNU General Public License for more details.
12  *
13  * You should have received a copy of the GNU General Public License
14  * along with this program. If not, see <http://www.gnu.org/licenses/>.
15  *
16  * @package VisionX::ArmarXObjects::BlurrinessMetric
17  * @author David Sippel ( uddoe at student dot kit dot edu )
18  * @date 2017
19  * @copyright http://www.gnu.org/licenses/gpl-2.0.txt
20  * GNU General Public License
21  */
22 
23 #include "BlurrinessMetric.h"
24 
25 
27 
28 using namespace armarx;
29 
30 
32 {
35 }
36 
37 
39 {
40  providerName = getProperty<std::string>("providerName").getValue();
41  usingImageProvider(providerName);
42 
43  offeringTopic(getProperty<std::string>("DebugObserverName").getValue());
44  frameRate = getProperty<float>("Framerate").getValue();
45  thresholdLaplace = getProperty<float>("ThresholdLaplaceBlur").getValue();
46  thresholdPerceptual = getProperty<float>("ThresholdPerceptualBlur").getValue();
47 }
48 
50 {
51  std::unique_lock lock(imageMutex);
52 
53  visionx::ImageProviderInfo imageProviderInfo = getImageProvider(providerName);
54  imageProviderPrx = getProxy<visionx::ImageProviderInterfacePrx>(providerName);
55 
56  cameraImages = new CByteImage*[2];
57  cameraImages[0] = visionx::tools::createByteImage(imageProviderInfo);
58  cameraImages[1] = visionx::tools::createByteImage(imageProviderInfo);
59 
60 
61  debugObserver = getTopic<DebugObserverInterfacePrx>(getProperty<std::string>("DebugObserverName").getValue());
62 
63  //enableResultImages(0, imageProviderPrx->getImageFormat().dimension, imageProviderPrx->getImageFormat().type);
64 
65  seq = 0;
66 
67 }
68 
70 {
71 }
72 
74 {
75  std::unique_lock lock(imageMutex);
76 
77  if (!waitForImages(getProperty<std::string>("providerName").getValue(), 1000))
78  {
79  ARMARX_WARNING << "Timeout while waiting for camera images (>1000ms)";
80  return;
81  }
82 
83  int numImages = getImages(cameraImages);
84 
85  if (numImages == 0)
86  {
87  ARMARX_WARNING << "Didn't receive one image! Aborting!";
88  return;
89  }
90 
91 
92 
93  IplImage* ppIplImages[1] = { IplImageAdaptor::Adapt(cameraImages[0]) };
94 
95  cv::Mat image = cv::cvarrToMat(ppIplImages[0]);
96 
97  cv::Mat gray_image;
98  cv::cvtColor(image, gray_image, cv::COLOR_BGR2GRAY);
99 
100  double blurrinessLaplaceVariance = laplaceVarianceBlurrinessMetric(gray_image);
101  double blurrinessPerceptualBlur = blurringPerceptual(gray_image);
102  double blurrinessMarziliano = blurringMarziliano(gray_image);
103 
104  ARMARX_LOG << deactivateSpam(1) << "blurrinessLaplaceVariance: " << ((blurrinessLaplaceVariance < thresholdLaplace) ? "Blurry" : "Not blurry") << " Value: " << blurrinessLaplaceVariance;
105  ARMARX_LOG << deactivateSpam(1) << "blurrinessPerceptialBlur: " << ((blurrinessPerceptualBlur > thresholdPerceptual) ? "Blurry" : "Not blurry") << " Value: " << blurrinessPerceptualBlur;
106  ARMARX_LOG << deactivateSpam(1) << "blurrinessMarziliano: " << blurrinessMarziliano;
107 
108  StringVariantBaseMap debugValues;
109  debugValues["BlurrinessValueLaplace"] = new Variant(blurrinessLaplaceVariance);
110  debugValues["BlurryLaplace"] = new Variant((blurrinessLaplaceVariance < thresholdLaplace));
111 
112  debugValues["BlurrinessValuePerceptual"] = new Variant(blurrinessPerceptualBlur);
113  debugValues["BlurryPerceptual"] = new Variant((blurrinessPerceptualBlur > thresholdPerceptual));
114 
115  debugValues["BlurrinessValueMarziliano"] = new Variant(blurrinessMarziliano);
116 
117  debugValues["seq"] = new Variant((int) seq);
118  seq++;
119 
120  debugObserver->setDebugChannel("BlurrinessMetric", debugValues);
121 
122  CByteImage* resultImages[1] = { IplImageAdaptor::Adapt(ppIplImages[0]) };
123  provideResultImages(resultImages);
124 
125  if (frameRate > 0.0)
126  {
127  fpsCounter.assureFPS(frameRate);
128  }
129 
130 }
131 
132 /**
133  * @brief armarx::BlurrinessMetric::laplaceVarianceBlurrinessMetric
134  * 'LAPV' algorithm from Pech et al. (2000)
135  * decsai.ugr.es/vip/files/conferences/Autofocusing2000.pdf
136  * @param in Input image as matrix
137  * @return blurriness value
138  */
139 double armarx::BlurrinessMetric::laplaceVarianceBlurrinessMetric(cv::Mat& in)
140 {
141  cv::Mat out;
142  cv::Laplacian(in, out, CV_64F);
143 
144  cv::Scalar mean, variance;
145  cv::meanStdDev(out, mean, variance);
146 
147  return (variance.val[0] * variance.val[0]);
148 }
149 
150 /**
151  * @brief blurringPerceptual
152  * @inproceedings{crete2007blur,
153  title={The blur effect: Perception and estimation with a new no-reference perceptual blur metric},
154  author={Cr{\'e}t{\'e}-Roffet, Fr{\'e}d{\'e}rique and Dolmiere, Thierry and Ladret, Patricia and Nicolas, Marina},
155  booktitle={SPIE Electronic Imaging Symposium Conf Human Vision and Electronic Imaging},
156  volume={12},
157  pages={EI--6492},
158  year={2007}
159  }
160  * @param src Input image as matrix
161  * @return blurriness value
162  */
163 double armarx::BlurrinessMetric::blurringPerceptual(const cv::Mat& src)
164 {
165  double blur_index = 0;
166 
167  cv::Mat smoothV(src.rows, src.cols, CV_8UC1);
168  cv::Mat smoothH(src.rows, src.cols, CV_8UC1);
169  cv::blur(src, smoothV, cv::Size(1, 9));
170  cv::blur(src, smoothH, cv::Size(9, 1));
171 
172 
173  double difS_V = 0, difS_H = 0, difB_V = 0, difB_H = 0;
174  double somaV = 0, somaH = 0, varV = 0, varH = 0;
175 
176  for (int i = 0; i < src.rows; ++i)
177  {
178 
179  for (int j = 0; j < src.cols; ++j)
180  {
181 
182  if (i >= 1)
183  {
184  difS_V = abs(src.at<uchar>(i, j) - src.at<uchar>(i - 1, j));
185  difB_V = abs(smoothV.at<uchar>(i, j) - smoothV.at<uchar>(i - 1, j));
186  }
187 
188  if (j >= 1)
189  {
190  difS_H = abs(src.at<uchar>(i, j) - src.at<uchar>(i, j - 1));
191  difB_H = abs(smoothH.at<uchar>(i, j) - smoothH.at<uchar>(i, j - 1));
192  }
193 
194  varV += cv::max(0.0, difS_V - difB_V);
195  varH += cv::max(0.0, difS_H - difB_H);
196  somaV += difS_V;
197  somaH += difS_H;
198  }
199  }
200 
201  blur_index = cv::max((somaV - varV) / somaV, (somaH - varH) / somaH);
202 
203  return blur_index;
204 }
205 
206 
207 /**
208  * @brief blurringMarziliano
209  * @ARTICLE{Marziliano04perceptualblur,
210  author = {Pina Marziliano and Frederic Dufaux and Stefan Winkler and Touradj Ebrahimi},
211  title = {Perceptual blur and ringing metrics: Application to JPEG2000,” Signal Process},
212  journal = {Image Commun},
213  year = {2004},
214  pages = {163--172} }
215  * @param src Input image as matrix
216  * @return blurriness value
217  */
218 double armarx::BlurrinessMetric::blurringMarziliano(const cv::Mat& src)
219 {
220  double blur_index = 0;
221 
222  cv::Mat edges(src.rows, src.cols, CV_8UC1);
223  cv::Mat element = cv::getStructuringElement(cv::MORPH_RECT, cv::Size(3, 3));
224 
225  cv::GaussianBlur(src, edges, cv::Size(3, 3), 0);
226  cv::morphologyEx(edges, edges, cv::MORPH_OPEN, element);
227  cv::morphologyEx(edges, edges, cv::MORPH_CLOSE, element);
228  cv::Sobel(edges, edges, CV_8UC1, 1, 0);
229 
230  unsigned int edge_counter = 0;
231  int c_start;
232  int c_end;
233  int k;
234 
235  uchar max = 0;
236  uchar min = 255;
237 
238  int length = 0;
239 
240  for (int i = 0; i < src.rows; ++i)
241  {
242  for (int j = 0; j < src.cols; ++j)
243  {
244 
245  c_start = -1;
246  c_end = -1;
247 
248  if (edges.at<uchar>(i, j) > 0)
249  {
250  edge_counter++;
251 
252  /** Left side of the border */
253  if (j == 0)
254  {
255  c_start = 0;
256  }
257  else
258  {
259  /** Check the first derivate */
260  if ((src.at<uchar>(i, j - 1) - src.at<uchar>(i, j)) > 0)
261  {
262  k = j;
263  max = src.at<uchar>(i, k);
264  while ((max <= src.at<uchar>(i, k - 1)) && (k > 1))
265  {
266  k--;
267  max = src.at<uchar>(i, k);
268  c_start = k;
269  }
270  }
271  else /* (src.at<uchar>(i,j-1) - src.at<uchar>(i,j)) < 0 */
272  {
273  k = j;
274  min = src.at<uchar>(i, k);
275  while ((min >= src.at<uchar>(i, k - 1)) && (k > 1))
276  {
277  k--;
278  min = src.at<uchar>(i, k);
279  c_start = k;
280  }
281  }
282  }
283 
284  /** Right side of the border */
285  if (j == (src.cols - 1))
286  {
287  c_end = src.cols - 1;
288  }
289  else
290  {
291  /** Check the first derivate */
292  if ((src.at<uchar>(i, j + 1) - src.at<uchar>(i, j)) > 0)
293  {
294  k = j;
295  max = src.at<uchar>(i, k);
296  while (max <= src.at<uchar>(i, k + 1))
297  {
298  k++;
299  max = src.at<uchar>(i, k);
300  c_end = k;
301  if (k == src.cols - 1)
302  {
303  break;
304  }
305  }
306  }
307  else /* (src.at<uchar>(i,j+1) - src.at<uchar>(i,j)) <= 0 */
308  {
309  k = j;
310  min = src.at<uchar>(i, k);
311  while (min >= src.at<uchar>(i, k + 1))
312  {
313  k++;
314  min = src.at<uchar>(i, k);
315  c_end = k;
316  if (k == src.cols - 1)
317  {
318  break;
319  }
320  }
321  }
322  }
323 
324  assert((c_end - c_start) >= 0);
325  length += (c_end - c_start);
326 
327  } /* if(edges.at<uchar>(i,j) > 0) */
328  }
329  }
330 
331  if (edge_counter != 0)
332  {
333  blur_index = ((double) length) / edge_counter;
334  }
335  else
336  {
337  blur_index = 0;
338  }
339 
340  return blur_index;
341 }
armarx::Variant
The Variant class is described here: Variants.
Definition: Variant.h:224
armarx::BlurrinessMetric::onExitImageProcessor
void onExitImageProcessor() override
Exit the ImapeProcessor component.
Definition: BlurrinessMetric.cpp:69
armarx::StringVariantBaseMap
std::map< std::string, VariantBasePtr > StringVariantBaseMap
Definition: ManagedIceObject.h:111
armarx::max
std::vector< T > max(const std::vector< T > &v1, const std::vector< T > &v2)
Definition: VectorHelpers.h:267
visionx::tools::createByteImage
CByteImage * createByteImage(const ImageFormatInfo &imageFormat, const ImageType imageType)
Creates a ByteImage for the destination type specified in the given imageProviderInfo.
visionx::ImageProviderInfo
Definition: ImageProcessor.h:466
deactivateSpam
SpamFilterDataPtr deactivateSpam(SpamFilterDataPtr const &spamFilter, float deactivationDurationSec, const std::string &identifier, bool deactivate)
Definition: Logging.cpp:72
ObserverObjectFactories.h
armarx::abs
std::vector< T > abs(const std::vector< T > &v)
Definition: VectorHelpers.h:253
armarx::mean
std::optional< float > mean(const boost::circular_buffer< NameValueMap > &buffer, const std::string &key)
Definition: KinematicUnitGuiPlugin.cpp:1615
armarx::BlurrinessMetricPropertyDefinitions
Definition: BlurrinessMetric.h:49
max
T max(T t1, T t2)
Definition: gdiam.h:48
ARMARX_LOG
#define ARMARX_LOG
Definition: Logging.h:163
armarx::BlurrinessMetric::process
void process() override
Process the vision component.
Definition: BlurrinessMetric.cpp:73
armarx::Component::getConfigIdentifier
std::string getConfigIdentifier()
Retrieve config identifier for this component as set in constructor.
Definition: Component.cpp:74
IceUtil::Handle< class PropertyDefinitionContainer >
armarx::min
std::vector< T > min(const std::vector< T > &v1, const std::vector< T > &v2)
Definition: VectorHelpers.h:294
Scalar
float Scalar
Definition: basic.h:14
armarx::BlurrinessMetric::onConnectImageProcessor
void onConnectImageProcessor() override
Implement this method in the ImageProcessor in order execute parts when the component is fully initia...
Definition: BlurrinessMetric.cpp:49
armarx::BlurrinessMetric::onInitImageProcessor
void onInitImageProcessor() override
Setup the vision component.
Definition: BlurrinessMetric.cpp:38
ARMARX_WARNING
#define ARMARX_WARNING
Definition: Logging.h:186
armarx::PropertyDefinitionsPtr
IceUtil::Handle< class PropertyDefinitionContainer > PropertyDefinitionsPtr
PropertyDefinitions smart pointer type.
Definition: forward_declarations.h:34
armarx::BlurrinessMetric::createPropertyDefinitions
armarx::PropertyDefinitionsPtr createPropertyDefinitions() override
Definition: BlurrinessMetric.cpp:31
armarx
This file offers overloads of toIce() and fromIce() functions for STL container types.
Definition: ArmarXTimeserver.cpp:28
BlurrinessMetric.h