35 #include <opencv2/core/core.hpp>
36 #include <opencv2/core/core_c.h>
37 #include <opencv2/opencv.hpp>
48 double min_x,
double max_x,
49 double min_y,
double max_y,
double rotation ) {
50 init(width_pixel, height_pixel, min_x, max_x, min_y, max_y, rotation);
55 return mapLayers_.size();
60 mapLayers_.resize ( _n );
64 for(
size_t i = 0; i < mapLayers_.size(); i++){ mapLayers_[i].create ( width(), height(), CV_32FC1 ); clearLayer(i); }
68 for(
size_t i = 0; i < mapLayers_.size(); i++){ clearLayer(i); }
71 mapLayers_[_layer].setTo( 1 );
75 return mapLayers_[_layer];
78 return mapLayers_[_layer];
84 Point2D mapPos = w2m(_worldPos);
85 if (!mapPos.
inside(0, 0, mapLayer(_layer).rows - 1, mapLayer(_layer).cols - 1))
89 const double mapPos_row_d = mapPos.
y() , mapPos_col_d = mapPos.
x();
90 const int mapPos_row_i = int(mapPos_row_d), mapPos_col_i = int(mapPos_col_d);
92 switch ( _interpolationType )
95 retVal = mapLayer(_layer).at<float_t>( mapPos_row_i, mapPos_col_i );
100 const double f00 = mapLayer(_layer).at<float_t>(mapPos_row_i , mapPos_col_i );
101 const double f10 = mapLayer(_layer).at<float_t>(mapPos_row_i + 1, mapPos_col_i );
102 const double f01 = mapLayer(_layer).at<float_t>(mapPos_row_i , mapPos_col_i + 1);
103 const double f11 = mapLayer(_layer).at<float_t>(mapPos_row_i + 1, mapPos_col_i + 1);
105 const double mapPosRed_row = mapPos_row_d - mapPos_row_i, mapPosRed_col = mapPos_col_d - mapPos_col_i;
107 retVal = f00 * (1 - mapPosRed_row) * (1 - mapPosRed_col) +
108 f10 * mapPosRed_row * (1 - mapPosRed_col) +
109 f01 * (1 - mapPosRed_row) * mapPosRed_col +
110 f11 * mapPosRed_row * mapPosRed_col;
118 if (
d < threshold ) {
119 p = tanh ( ( 2*M_PI*-
d ) /threshold+M_PI ) * 0.5 + 0.5;
125 if (
d < threshold ) {
132 Mat srcMap; srcMap.create ( width(), height(), CV_32FC1 ); srcMap.setTo ( 1 );
134 if(connectPoints){
for (
size_t i = 1; i < _pSrc.size(); i++ ) { line ( srcMap, _pSrc[i-1], _pSrc[i], colour, 8); } }
135 else {
for (
size_t i = 0; i < _pSrc.size(); i++ ) { circle ( srcMap, _pSrc[i], 1, colour, 1, 8); } }
136 computeDistanceField ( _mDst, srcMap, _radius, _flipDistance );
142 _mSrc.convertTo(srcMap, CV_8U);
144 int maskSize0 = cv::DIST_MASK_PRECISE;
145 int voronoiType = -1;
146 int distType0 = cv::DIST_L2;
147 int maskSize = voronoiType >= 0 ? cv::DIST_MASK_5 : maskSize0;
148 int distType = voronoiType >= 0 ? cv::DIST_L2 : distType0;
149 Mat destMap_f, labels;
151 if ( voronoiType < 0 ){ cv::distanceTransform ( srcMap, destMap_f, distType, maskSize ); }
152 else { cv::distanceTransform ( srcMap, destMap_f, labels, distType, maskSize, voronoiType ); }
155 CV_Assert(destMap_f.depth() == CV_32F);
156 int channels = destMap_f.channels();
157 int nRows = destMap_f.rows;
158 int nCols = destMap_f.cols * channels;
159 if (destMap_f.isContinuous()) { nCols *= nRows; nRows = 1; }
161 float threshold = _radius * scale_x ();
162 float_t* p_d;
float* p_s;
163 for(
int i = 0; i < nRows; ++i) {
164 p_d = destMap_f.ptr<float_t>(i);
168 if ( ( _mDst.channels() != 1 ) && ( _mDst.channels() != 5 ) ) {
cvtColor(destMap_f, _mDst, cv::COLOR_GRAY2BGR ); }
169 else { _mDst = destMap_f; }