29 #include <image_transport/image_transport.h>
30 #include <cv_bridge/cv_bridge.h>
31 #include <sensor_msgs/image_encodings.h>
32 #include <opencv2/imgproc/imgproc.hpp>
33 #include <opencv2/highgui/highgui.hpp>
42 image_transport::ImageTransport
it_;
62 std::cout << std::endl;
63 std::cout << std::endl;
64 std::cout <<
"Foram lidas: " << total <<
" DataMatrix" << std::endl;
69 if (
leituras[j] !=
"111222") error++;
73 std::cout <<
"Das quais: " << error <<
" foram lidas erradamente" << std::endl;
74 std::cout <<
"Success rate: " << ((total - error)/static_cast<double>(total))*100. <<
" %" << std::endl;
75 std::cout << std::endl;
80 cv_bridge::CvImagePtr cv_ptr;
83 cv_ptr = cv_bridge::toCvCopy(msg, sensor_msgs::image_encodings::BGR8);
85 catch (cv_bridge::Exception& e)
87 ROS_ERROR(
"cv_bridge exception: %s", e.what());
97 cv::imshow(
"Imagem", cv_ptr->image);
112 cvtColor(cv_img, gray_img, CV_BGR2GRAY, 0);
117 img = dmtxImageCreate(gray_img.data, gray_img.cols, gray_img.rows, DmtxPack8bppK);
120 dec = dmtxDecodeCreate(img, 1);
124 DmtxTime timeout = dmtxTimeAdd(dmtxTimeNow(),50);
125 reg = dmtxRegionFindNext(dec, &timeout);
127 msg = dmtxDecodeMatrixRegion(dec, reg, DmtxUndefined);
133 std::cout <<
"output " << i++ <<
": " << msg->output << std::endl;
134 leituras.push_back(std::string((
char*)(msg->output)));
137 dmtxMessageDestroy(&msg);
140 int height = cv_img.rows-1;
141 cv::circle(cv_img, cv::Point (reg->leftLoc.X, height - reg->leftLoc.Y), 10, CV_RGB(255,0,0));
142 cv::circle(cv_img, cv::Point (reg->rightLoc.X, height - reg->rightLoc.Y), 10, CV_RGB(255,0,0));
143 cv::circle(cv_img, cv::Point (reg->topLoc.X, height - reg->topLoc.Y), 10, CV_RGB(255,0,0));
144 cv::circle(cv_img, cv::Point (reg->bottomLoc.X, height - reg->bottomLoc.Y), 10, CV_RGB(255,0,0));
146 dmtxRegionDestroy(®);
152 dmtxDecodeDestroy(&dec);
153 dmtxImageDestroy(&img);
158 int main(
int argc,
char** argv)
160 ros::init(argc, argv,
"read_gray_datamatrix");
void DatamatrixDecode(cv::Mat &cv_img)
int main(int argc, char **argv)
std::vector< std::string > leituras
void imageCallback(const sensor_msgs::ImageConstPtr &msg)
image_transport::ImageTransport it_
image_transport::Subscriber image_sub_