Package-Identification-using-Turtlebot
Robots have been used to improve efficiency in a various tasks in warehouses such as package handling, identification and organization. This project aims to simulate the use of Turtlebot in identifying packages with QR codes, in a warehouse setting.
QReader.hpp
Go to the documentation of this file.
1 
39 #ifndef INCLUDE_PACKAGE_IDENTIFICATION_USING_TURTLEBOT_QREADER_HPP_
40 #define INCLUDE_PACKAGE_IDENTIFICATION_USING_TURTLEBOT_QREADER_HPP_
41 
42 #include <image_transport/image_transport.h>
43 #include <vector>
44 #include <opencv2/opencv.hpp>
45 
50 class QReader {
51  public:
55  QReader();
56 
60  ~QReader();
61 
70  void imageCb(const sensor_msgs::ImageConstPtr& msg);
71 
72  cv::Mat processFrame();
81  std::vector<uint8_t> decodeQR();
82 
90  std::vector<uint8_t> returnBytes();
91 
99  void setImage(cv::Mat image);
100 
101  private:
105  image_transport::Subscriber imgSub;
109  std::vector<uint8_t> bytes;
113  ros::NodeHandle nh;
117  cv::Mat img;
121  std::vector<cv::Point2f> possibleCenters;
125  std::vector<float> estimatedModuleSize;
129  int dimension = 21;
133  image_transport::ImageTransport it;
134 
145  bool checkQCodeExists(cv::Mat&);
154  bool checkRatio(std::vector<int>);
166  bool isFinderPattern(const cv::Mat&, std::vector<int>, int, int);
179  float checkVertical(const cv::Mat&, int, int, int, int);
193  float checkHorizontal(const cv::Mat&, int, int, int, int);
206  bool checkDiagonal(const cv::Mat&, float, float, int, int);
214  float columnCenterEstimate(std::vector<int>, int);
215 
223  cv::Mat warpToCode(cv::Mat&);
231  std::vector<std::vector<bool> > extractBits(cv::Mat&);
237  void unmask(std::vector<std::vector<bool> >&);
238 
244  std::vector<uint8_t> decodeArray(const std::vector<std::vector<bool> >&);
245 
256  uint8_t getNumberValue(std::vector<bool>::iterator&, unsigned int);
257 };
258 
259 #endif // INCLUDE_PACKAGE_IDENTIFICATION_USING_TURTLEBOT_QREADER_HPP_
void setImage(cv::Mat image)
Sets the value for the private value img.
Definition: QReader.cpp:732
std::vector< uint8_t > returnBytes()
Function to get the extracted data array.
Definition: QReader.cpp:65
QReader()
Constructs a object.
Definition: QReader.cpp:56
~QReader()
Destroys the object.
Definition: QReader.cpp:63
std::vector< uint8_t > decodeQR()
A function to get the raw image, find the QR code, unmask the QR code and decode the QR code in the i...
Definition: QReader.cpp:154
cv::Mat processFrame()
Definition: QReader.cpp:83
void imageCb(const sensor_msgs::ImageConstPtr &msg)
A function to get the raw image, from the camera and convert it to cv::Mat format using cv bridge...
Definition: QReader.cpp:67
Class QReader has methods to get the image and decode the QR code in the image to extract data of pac...
Definition: QReader.hpp:50