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.
PathPlanner.hpp
Go to the documentation of this file.
1 
41 #ifndef INCLUDE_PACKAGE_IDENTIFICATION_USING_TURTLEBOT_PATHPLANNER_HPP_
42 #define INCLUDE_PACKAGE_IDENTIFICATION_USING_TURTLEBOT_PATHPLANNER_HPP_
43 
44 #include <geometry_msgs/PoseWithCovarianceStamped.h>
45 #include <move_base_msgs/MoveBaseAction.h>
46 #include <ros/ros.h>
47 #include <string>
48 #include <vector>
50 
56 class PathPlanner {
57  private:
61  ros::NodeHandle nh;
66  ros::Publisher initPosePub;
70  geometry_msgs::PoseWithCovarianceStamped initialPose;
74  std::vector<move_base_msgs::MoveBaseGoal> goal;
78  QReader reader;
79 
83  int counter;
91  std::vector<double> publishInitPose(double x, double y, double w);
92 
93  public:
99  explicit PathPlanner(std::vector<std::vector<double>>);
105  ~PathPlanner();
111  ros::Publisher returnPublisher();
119  std::vector<double> callPublisher(double, double, double);
126  std::vector<std::string> callVision(std::vector<std::string>);
132  std::vector<std::string> sendGoals();
138  int findPackage(std::vector<std::string>);
145  std::string waitPackageDetection(std::string);
146 };
147 
148 #endif // INCLUDE_PACKAGE_IDENTIFICATION_USING_TURTLEBOT_PATHPLANNER_HPP_
Class PathPlanner has methods send goal points and initial pose of the turtlebot to move_base package...
Definition: PathPlanner.hpp:56
std::vector< std::string > sendGoals()
Method to send goals to move_base action server.
Definition: PathPlanner.cpp:129
std::string waitPackageDetection(std::string)
Method to try again if the package detection is faulty.
Definition: PathPlanner.cpp:98
std::vector< double > callPublisher(double, double, double)
Method to call publishInitPose.
Definition: PathPlanner.cpp:93
ros::Publisher returnPublisher()
Method that returns publisher object.
Definition: PathPlanner.cpp:75
~PathPlanner()
Destructor of the PathPlanner class.
Definition: PathPlanner.cpp:73
PathPlanner(std::vector< std::vector< double >>)
Constructor of the PathPlanner class.
Definition: PathPlanner.cpp:49
File that has declarations for the QReader class.
int findPackage(std::vector< std::string >)
Method to print the packIDs and their location where to find them.
Definition: PathPlanner.cpp:162
std::vector< std::string > callVision(std::vector< std::string >)
Method to call callback function from QReader class.
Definition: PathPlanner.cpp:114
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