datamatrix_detection_node.cpp
Go to the documentation of this file.
1 /**************************************************************************************************
2  Software License Agreement (BSD License)
3 
4  Copyright (c) 2011-2014, LAR toolkit developers - University of Aveiro - http://lars.mec.ua.pt
5  All rights reserved.
6 
7  Redistribution and use in source and binary forms, with or without modification, are permitted
8  provided that the following conditions are met:
9 
10  *Redistributions of source code must retain the above copyright notice, this list of
11  conditions and the following disclaimer.
12  *Redistributions in binary form must reproduce the above copyright notice, this list of
13  conditions and the following disclaimer in the documentation and/or other materials provided
14  with the distribution.
15  *Neither the name of the University of Aveiro nor the names of its contributors may be used to
16  endorse or promote products derived from this software without specific prior written permission.
17 
18  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR
19  IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND
20  FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
21  CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
22  DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
23  DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER
24  IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT
25  OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 ***************************************************************************************************/
27 
28 #include <iostream>
29 #include <string>
30 
31 #include <ros/ros.h>
32 
33 #include <datamatrix_detection/DatamatrixMsg.h>
34 
35 #include <image_transport/image_transport.h>
36 #include <cv_bridge/cv_bridge.h>
37 #include <sensor_msgs/image_encodings.h>
38 
39 #include <opencv2/imgproc/imgproc.hpp>
40 #include <opencv2/highgui/highgui.hpp>
41 
42 #include <dmtx.h>
43 
44 class ImageConverter
45 {
46  ros::NodeHandle nh_;
47  ros::Publisher datamatrix_pub;
48 
49  image_transport::ImageTransport it_;
50  image_transport::Subscriber image_sub_;
51 
52  std::vector<double> elapsed_time;
53 
54 // std::vector<std::string> leituras;
55 
56 public:
58  : it_(nh_)
59  {
60  // Subscribe to input video feed and publish output video feed
61  image_sub_ = it_.subscribe("usb_cam_reader/image_rect_color", 1,
63  datamatrix_pub = nh_.advertise<datamatrix_detection::DatamatrixMsg>("datamatrix_detection/datamatrix_msg",1);
64  }
65 
67  {
68 
69  double sum_time=0, max_time = 0.0, min_time = 1000;
70 
71  for( int i = 0 ; i<elapsed_time.size();i++)
72  {
73  sum_time = sum_time + elapsed_time[i];
74  if (elapsed_time[i] < min_time)
75  min_time = elapsed_time[i];
76  if (elapsed_time[i] > max_time)
77  max_time = elapsed_time[i];
78  }
79 
80  std::cout << "Detection: " << std::endl;
81  std::cout << "max time: " << max_time*1000 << " min time: " << min_time*1000 << " mean time: " << sum_time*1000/elapsed_time.size() << std::endl;
82 
83 // uint total = leituras.size();
84 // std::cout << std::endl;
85 // std::cout << "Foram lidas: " << total << " DataMatrix" << std::endl;
86 // int error = 0;
87 // uint j;
88 // for ( j=0; j < leituras.size(); j++)
89 // {
90 // if (leituras[j] != "111222") error++;
91 //
92 // }
93 //
94 // std::cout << "Das quais: " << error << " foram lidas erradamente" << std::endl;
95 // std::cout << "Success rate: " << ((total - error)/static_cast<double>(total))*100. << " %" << std::endl;
96 // std::cout << std::endl;
97  }
98 
99  void imageCallback(const sensor_msgs::ImageConstPtr& msg)
100  {
101  cv_bridge::CvImagePtr cv_ptr;
102  try
103  {
104  cv_ptr = cv_bridge::toCvCopy(msg, sensor_msgs::image_encodings::BGR8);
105  }
106  catch (cv_bridge::Exception& e)
107  {
108  ROS_ERROR("cv_bridge exception: %s", e.what());
109  return;
110  }
111 // ros::Time start = ros::Time::now();
112  DatamatrixDecode(cv_ptr->image,cv_ptr->header);
113 // elapsed_time.push_back( fabs((ros::Time::now() - start).toSec()) );
114 
115  // Update GUI Window
116 // cv::imshow("Image", cv_ptr->image);
117 // cv::waitKey(3);
118 
119  }
120 
121  void DatamatrixDecode(cv::Mat& cv_ori_img, std_msgs::Header image_header)
122  {
123  ros::Time start = ros::Time::now();
124 
125 // static int i = 1;
126  DmtxImage *img;
127  DmtxDecode *dec;
128  DmtxRegion *reg;
129  DmtxMessage *msg;
130 // int height = cv_img.rows-1;
131 
132 // Rotate image
133 
134  cv::Mat rot_img;
135  cv::Mat rot_mat = getRotationMatrix2D(cv::Point(cv_ori_img.cols/2, cv_ori_img.rows/2), 180, 1);
136  cv::warpAffine(cv_ori_img, rot_img, rot_mat, cv_ori_img.size());
137 
138  cv::Mat cv_img = rot_img.rowRange(rot_img.rows/4, 3 * rot_img.rows/4);
139  int height = cv_img.rows-1 + rot_img.rows/4;
140 
141 // cv::Mat cv_img = cv_ori_img.rowRange(cv_ori_img.rows/4, 3 * cv_ori_img.rows/4);
142 // int height = cv_img.rows-1 + cv_ori_img.rows/4;
143 
144 // ImageFilter
145 // cv::Mat imgHSV;
146 // cv::cvtColor(cv_img, imgHSV, cv::COLOR_BGR2HSV); //Convert the captured frame from BGR to HSV
147 //
148 // cv::Mat imgThresholded;
149 // cv::inRange(imgHSV, cv::Scalar(0, 0, 0), cv::Scalar(179, 255, 100), imgThresholded); //Threshold the image
150 //
151 // cv_img = imgThresholded.clone();
152 
153 
154  datamatrix_detection::DatamatrixMsg datamatrix_msg;
155  datamatrix_detection::DatamatrixData datamatrix_data;
156  datamatrix_msg.header = image_header;
157 
158  img = dmtxImageCreate(cv_img.data, cv_img.cols, cv_img.rows, DmtxPack24bppRGB);
159  assert(img != NULL);
160 
161  dec = dmtxDecodeCreate(img, 1);
162  assert(dec != NULL);
163 
164  // For multiple matrix reading =========================================================
165  int delay = 80; // Delay in miliseconds
166  DmtxTime timeout = dmtxTimeAdd(dmtxTimeNow(),delay); // adds 50 miliseconds to the timeout time [now + 50ms]
167  reg = dmtxRegionFindNext(dec, &timeout);
168  while(reg != NULL) {
169  msg = dmtxDecodeMatrixRegion(dec, reg, DmtxUndefined);
170  if(msg != NULL) {
171  datamatrix_data.code = std::string((char*)(msg->output));
172 
173  datamatrix_data.left.x = reg->leftLoc.X;
174  datamatrix_data.left.y = height - reg->leftLoc.Y;
175  datamatrix_data.left.z = 0;
176  datamatrix_data.right.x = reg->rightLoc.X;
177  datamatrix_data.right.y = height - reg->rightLoc.Y;
178  datamatrix_data.right.z = 0;
179  datamatrix_data.top.x = reg->topLoc.X;
180  datamatrix_data.top.y = height - reg->topLoc.Y;
181  datamatrix_data.top.z = 0;
182  datamatrix_data.bottom.x = reg->bottomLoc.X;
183  datamatrix_data.bottom.y = height - reg->bottomLoc.Y;
184  datamatrix_data.bottom.z = 0;
185 
186  datamatrix_msg.decoded_matrices.push_back(datamatrix_data);
187 
188  dmtxMessageDestroy(&msg);
189  }
190 
191  timeout = dmtxTimeAdd(dmtxTimeNow(),delay); // It searches for matrixes in the image for delay miliseconds each one
192  reg = dmtxRegionFindNext(dec, &timeout);
193 
194  }
195 
196 // datamatrix_detection::DatamatrixMsg datamatrix_msg Publish
197  datamatrix_pub.publish(datamatrix_msg);
198 
199  dmtxDecodeDestroy(&dec);
200  dmtxImageDestroy(&img);
201  dmtxRegionDestroy(&reg);
202 
203  if ( msg !=NULL)
204  elapsed_time.push_back( fabs((ros::Time::now() - start).toSec()) );
205 // cv::imshow("ROImage",cv_img);
206  }
207 
208 };
209 
210 int main(int argc, char** argv)
211 {
212  ros::init(argc, argv, "datamatrix_detection");
213  ImageConverter ic;
214  ros::spin();
215  return 0;
216 }
void DatamatrixDecode(cv::Mat &cv_img)
int main(int argc, char **argv)
void DatamatrixDecode(cv::Mat &cv_ori_img, std_msgs::Header image_header)
void imageCallback(const sensor_msgs::ImageConstPtr &msg)
image_transport::ImageTransport it_
image_transport::Subscriber image_sub_
std::vector< double > elapsed_time


datamatrix_detection
Author(s): Luís Pedras Carrão
autogenerated on Mon Mar 2 2015 01:31:36