datamatrix/detector.cpp
Go to the documentation of this file.
1 #include "detector.h"
2 #include <dmtx.h>
3 
4 namespace detectors{
5 namespace datamatrix{
7  }
8 
9  bool Detector::detect(cv::Mat& image, int timeout, unsigned int offsetx, unsigned int offsety){
10  bool detected = false;
11  lines_.clear();
12  message_.clear();
13  polygon_.clear();
14  DmtxRegion *reg;
15  DmtxDecode *dec;
16  DmtxImage *img;
17  DmtxMessage *msg;
18  DmtxTime t;
19 
20  img = dmtxImageCreate(image.data, image.cols, image.rows, DmtxPack24bppRGB);
21  //dmtxImageSetProp(img, DmtxPropImageFlip, DmtxFlipY);
22 
23  dec = dmtxDecodeCreate(img, 1);
24  assert(dec != NULL);
25 
26  t = dmtxTimeAdd(dmtxTimeNow(), timeout);
27  reg = dmtxRegionFindNext(dec, &t);
28 
29  if(reg != NULL) {
30 
31  int height;
32  int dataWordLength;
33  int rotateInt;
34  double rotate;
35  DmtxVector2 p00, p10, p11, p01;
36 
37  height = dmtxDecodeGetProp(dec, DmtxPropHeight);
38 
39  p00.X = p00.Y = p10.Y = p01.X = 0.0;
40  p10.X = p01.Y = p11.X = p11.Y = 1.0;
41  dmtxMatrix3VMultiplyBy(&p00, reg->fit2raw);
42  dmtxMatrix3VMultiplyBy(&p10, reg->fit2raw);
43  dmtxMatrix3VMultiplyBy(&p11, reg->fit2raw);
44  dmtxMatrix3VMultiplyBy(&p01, reg->fit2raw);
45  polygon_.push_back(cv::Point(p00.X + offsetx,image.rows-p00.Y + offsety));
46  polygon_.push_back(cv::Point(p10.X + offsetx,image.rows-p10.Y + offsety));
47  polygon_.push_back(cv::Point(p11.X + offsetx,image.rows-p11.Y + offsety));
48  polygon_.push_back(cv::Point(p01.X + offsetx,image.rows-p01.Y + offsety));
49 
50  lines_.push_back(
51  std::pair<cv::Point,cv::Point>(
52  cv::Point(p00.X + offsetx,image.rows-p00.Y + offsety),
53  cv::Point(p10.X + offsetx,image.rows-p10.Y + offsety)
54  )
55  );
56  lines_.push_back(
57  std::pair<cv::Point,cv::Point>(
58  cv::Point(p10.X + offsetx,image.rows-p10.Y + offsety),
59  cv::Point(p11.X + offsetx,image.rows-p11.Y + offsety)
60  )
61  );
62  lines_.push_back(
63  std::pair<cv::Point,cv::Point>(
64  cv::Point(p11.X + offsetx,image.rows-p11.Y + offsety),
65  cv::Point(p01.X + offsetx,image.rows-p01.Y + offsety)
66  )
67  );
68  lines_.push_back(
69  std::pair<cv::Point,cv::Point>(
70  cv::Point(p01.X + offsetx,image.rows-p01.Y + offsety),
71  cv::Point(p00.X + offsetx,image.rows-p00.Y + offsety)
72  )
73  );
74  detected = true;
75  msg = dmtxDecodeMatrixRegion(dec, reg, DmtxUndefined);
76  if(msg != NULL) {
77  message_ = (const char*)msg->output;
78  dmtxMessageDestroy(&msg);
79  }
80  dmtxRegionDestroy(&reg);
81  }
82 
83  dmtxDecodeDestroy(&dec);
84  dmtxImageDestroy(&img);
85  return detected;
86  }
87 }
88 }
bool detect(cv::Mat &image, int timeout=1000, unsigned int offsetx=0, unsigned int offsety=0)
TFSIMD_FORCE_INLINE Vector3 rotate(const Vector3 &wAxis, const tfScalar angle) const
std::vector< cv::Point > polygon_
Definition: detector_base.h:13
std::vector< std::pair< cv::Point, cv::Point > > lines_
Definition: detector_base.h:12


visp_auto_tracker
Author(s): Filip Novotny
autogenerated on Sat Mar 13 2021 03:20:08