VisionUtils.h
Go to the documentation of this file.
1 /*
2  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9 
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 
18 #ifndef __IPA_VISIONUTILS_H__
19 #define __IPA_VISIONUTILS_H__
20 
21 
23 #include <opencv2/core/core.hpp>
24 #include <iostream>
25 
26 namespace ipa_Utils {
27 
28 
32 cv::Mat vstack(const std::vector<cv::Mat> &mats);
33 
41 unsigned long ConvertToShowImage(const cv::Mat& source, cv::Mat& dest, int channel = 1, double min = -1, double max = -1);
42 
55 unsigned long MaskImage(const cv::Mat& source, cv::Mat& dest, const cv::Mat& mask, cv::Mat& destMask, float minMaskThresh = 0,
56  float maxMaskTresh = 20000, int sourceChannel = 1, double sourceMin = -1, double sourceMax = -1);
57 
64 unsigned long EvaluatePolynomial(double x, int degree, double* coefficients, double* y);
65 
73 unsigned long FilterByAmplitude(cv::Mat& xyzImage, const cv::Mat& greyImage, cv::Mat* mask, cv::Mat* maskColor, float minMaskThresh, float maxMaskThresh);
74 
83 unsigned long FilterTearOffEdges(cv::Mat& xyzImage, cv::Mat* mask, float piHalfFraction = 6);
84 
86 unsigned long FilterSpeckles( cv::Mat& img, int maxSpeckleSize, double _maxDiff, cv::Mat& _buf );
87 
93 cv::Vec3b GrayColorMap(double value, double min, double max);
94 
99 unsigned long SaveMat(cv::Mat& mat, std::string filename, int type=CV_32F);
100 
105 unsigned long LoadMat(cv::Mat& mat, std::string filename, int type=CV_32F);
106 
107 
112 template <typename Distance>
113 void ClusteringKMeanspp(int k, cv::Mat& dataset, int* indices, int indices_length, int* centers, int& centers_length, int numLocalTries=1)
114 {
115  typedef typename Distance::ElementType ElementType;
116  typedef typename Distance::ResultType DistanceType;
117 
118  Distance distance = Distance();
119 
120  int n = indices_length;
121 
122  double currentPot = 0;
123  DistanceType* closestDistSq = new DistanceType[n];
124 
125  // Choose one random center and set the closestDistSq values
126  //int index = cv::flann::rand_int(n);
127  int index = rand() % n;
128  assert(index >=0 && index < n);
129  centers[0] = indices[index];
130 
131  for (int i = 0; i < n; i++) {
132  closestDistSq[i] = distance(dataset.ptr(indices[i]),
133  dataset.ptr(indices[index]), dataset.cols);
134  currentPot += closestDistSq[i];
135  }
136 
137  // Choose each center
138  int centerCount;
139  for (centerCount = 1; centerCount < k; centerCount++) {
140 
141  // Repeat several trials
142  double bestNewPot = -1;
143  int bestNewIndex = 0;
144  for (int localTrial = 0; localTrial < numLocalTries; localTrial++) {
145 
146  // Choose our center - have to be slightly careful to return a valid answer even accounting
147  // for possible rounding errors
148  //double randVal = cv::flann::rand_double(currentPot);
149  double randVal = (double)rand() / RAND_MAX;
150  double fMin = 0;
151  double fMax = currentPot;
152  randVal = fMin + randVal * (fMax - fMin);
153  for (index = 0; index < n-1; index++) {
154  if (randVal <= closestDistSq[index]) break;
155  else randVal -= closestDistSq[index];
156  }
157 
158  // Compute the new potential
159  double newPot = 0;
160  for (int i = 0; i < n; i++)
161  newPot += std::min( distance(dataset.ptr(indices[i]),
162  dataset.ptr(indices[index]), dataset.cols), closestDistSq[i] );
163 
164  // Store the best result
165  if ((bestNewPot < 0)||(newPot < bestNewPot)) {
166  bestNewPot = newPot;
167  bestNewIndex = index;
168  }
169  }
170 
171  // Add the appropriate center
172  centers[centerCount] = indices[bestNewIndex];
173  currentPot = bestNewPot;
174  for (int i = 0; i < n; i++)
175  closestDistSq[i] = std::min( distance(dataset.ptr(indices[i]),
176  dataset.ptr(indices[bestNewIndex]), dataset.cols), closestDistSq[i] );
177  }
178 
179  centers_length = centerCount;
180 
181  delete[] closestDistSq;
182 }
183 
184 // Generator that yields an increasing sequence of integers
186 public:
187  int current;
188  UniqueNumber();
189  int operator()();
190 };
191 
192 // Returns random subset of input vector. Will not create duplicates.
193 // @param v Input vector
194 // @param n Number of items to return
195 // @return Vector of same type as input vector (length n)
196 template<class T> std::vector<T> takeRandomN(const std::vector<T> &v, int n)
197 {
198  int current = 0;
199  std::vector<int> indices(v.size());
200  std::generate(indices.begin(), indices.end(), UniqueNumber());
201  std::random_shuffle(indices.begin(), indices.end());
202 
203  std::vector<T> ret;
204  for (int i = 0; i < n; i++)
205  {
206  ret.push_back(v[indices[i]]);
207  }
208 
209  return ret;
210 }
211 
212 } // end namespace __IPA_VISIONUTILS_H__
213 
214 
215 #endif
cv::Mat vstack(const std::vector< cv::Mat > &mats)
Definition: VisionUtils.cpp:26
unsigned long ConvertToShowImage(const cv::Mat &source, cv::Mat &dest, int channel=1, double min=-1, double max=-1)
unsigned long SaveMat(cv::Mat &mat, std::string filename, int type=CV_32F)
unsigned long FilterSpeckles(cv::Mat &img, int maxSpeckleSize, double _maxDiff, cv::Mat &_buf)
Description.
cv::Vec3b GrayColorMap(double value, double min, double max)
unsigned long LoadMat(cv::Mat &mat, std::string filename, int type=CV_32F)
unsigned long MaskImage(const cv::Mat &source, cv::Mat &dest, const cv::Mat &mask, cv::Mat &destMask, float minMaskThresh=0, float maxMaskTresh=20000, int sourceChannel=1, double sourceMin=-1, double sourceMax=-1)
Definition: VisionUtils.cpp:75
unsigned long EvaluatePolynomial(double x, int degree, double *coefficients, double *y)
Definition: VisionUtils.cpp:63
std::vector< T > takeRandomN(const std::vector< T > &v, int n)
Definition: VisionUtils.h:196
unsigned long FilterTearOffEdges(cv::Mat &xyzImage, cv::Mat *mask, float piHalfFraction=6)
unsigned long FilterByAmplitude(cv::Mat &xyzImage, const cv::Mat &greyImage, cv::Mat *mask, cv::Mat *maskColor, float minMaskThresh, float maxMaskThresh)
void ClusteringKMeanspp(int k, cv::Mat &dataset, int *indices, int indices_length, int *centers, int &centers_length, int numLocalTries=1)
Definition: VisionUtils.h:113


cob_vision_utils
Author(s): Jan Fischer
autogenerated on Sun Oct 18 2020 13:13:20