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.
Functions
PathPlannerTest.cpp File Reference

file to test the class PathPlanner More...

#include <cv_bridge/cv_bridge.h>
#include <gtest/gtest.h>
#include <ros/connection_manager.h>
#include <ros/package.h>
#include <ros/ros.h>
#include <vector>
#include "package_identification_using_turtlebot/PathPlanner.hpp"

Functions

void testCb (const geometry_msgs::PoseWithCovarianceStamped msg)
 
 TEST (publishInitPoseTest, testPlanner1)
 Test to check intiPose publisher. More...
 
 TEST (findPackageTest, testPlanner2)
 Test if findPackage executes successfully. More...
 
 TEST (callVisionTest, testPlanner3)
 Test to check if QR code is properly detected. More...
 
 TEST (waitPackageDetection, detectionCorrection)
 Test to check if a slanted QR code is properly detected. More...
 

Detailed Description

file to test the class PathPlanner

Author
RajendraMayavan
Adarsh Jagan

Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:

  1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer.
  2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution.
  3. Neither the name of the copyright holder nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission.

THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.

Function Documentation

TEST ( publishInitPoseTest  ,
testPlanner1   
)

Test to check intiPose publisher.

Parameters
[in]TESTSuite
[in]test
Returns
none
57  {
58  ros::NodeHandle nh;
59  PathPlanner planner({{0.0, 0.0, 0.0, 1.0}});
60  ros::Publisher pub = planner.returnPublisher();
61  ros::Subscriber sub = nh.subscribe("/initialpose", 1, &testCb);
62  EXPECT_EQ(pub.getNumSubscribers(), 1U);
63  EXPECT_EQ(sub.getNumPublishers(), 1U);
64  std::vector<double> res = planner.callPublisher(2.0, 1.0, 1.0);
65  ASSERT_EQ(res.at(0), 2.0);
66  ASSERT_EQ(res.at(1), 1.0);
67  ASSERT_EQ(res.at(2), 1.0);
68 }
Class PathPlanner has methods send goal points and initial pose of the turtlebot to move_base package...
Definition: PathPlanner.hpp:56
void testCb(const geometry_msgs::PoseWithCovarianceStamped msg)
Definition: PathPlannerTest.cpp:49
std::shared_ptr< ros::NodeHandle > nh
Definition: main.cpp:43
ros::Publisher returnPublisher()
Method that returns publisher object.
Definition: PathPlanner.cpp:75
TEST ( findPackageTest  ,
testPlanner2   
)

Test if findPackage executes successfully.

Parameters
[in]TESTSuite
[in]test
Returns
none
76  {
77  PathPlanner planner({{-2.0, -3.0, 0.0, 1.0}, {-1.0, -2.0, 0.0, 1.0}});
78  std::vector<std::string> packID;
79  packID.push_back("pack#1");
80  packID.push_back("pack#2");
81  int i = planner.findPackage(packID);
82  ASSERT_EQ(i, 0);
83 }
Class PathPlanner has methods send goal points and initial pose of the turtlebot to move_base package...
Definition: PathPlanner.hpp:56
int findPackage(std::vector< std::string >)
Method to print the packIDs and their location where to find them.
Definition: PathPlanner.cpp:162
TEST ( callVisionTest  ,
testPlanner3   
)

Test to check if QR code is properly detected.

Parameters
[in]TESTSuite
[in]test
Returns
none
91  {
92  ros::NodeHandle nh;
93  image_transport::ImageTransport it(nh);
94  // Advertise a known image on camera/rgb/image_raw topic
95  image_transport::Publisher pub = it.advertise("camera/rgb/image_raw", 1);
96  std::string fileLocation =
97  ros::package::getPath("package_identification_using_turtlebot") +
98  "/data/pack4.png";
99  cv::Mat image = cv::imread(fileLocation);
100  cv::waitKey(3);
101  sensor_msgs::ImagePtr msg =
102  cv_bridge::CvImage(std_msgs::Header(), "bgr8", image).toImageMsg();
103  ros::Rate loop_rate(5);
104  PathPlanner planner({{-2.0, -3.0, 0.0, 1.0}, {-1.0, -2.0, 0.0, 1.0}});
105  std::vector<std::string> packID;
106  ros::Time start_time = ros::Time::now();
107  ros::Duration timeout(15.0);
108  // If the test is not completed within timeout the test fails
109  while (ros::Time::now() - start_time < timeout) {
110  pub.publish(msg);
111  packID = planner.callVision(packID);
112  if (packID.at(0).substr(0, 4) == "pack") break;
113  loop_rate.sleep();
114  }
115 
116  ASSERT_STREQ("pack#4", (packID.at(0)).c_str());
117 }
Class PathPlanner has methods send goal points and initial pose of the turtlebot to move_base package...
Definition: PathPlanner.hpp:56
std::shared_ptr< ros::NodeHandle > nh
Definition: main.cpp:43
TEST ( waitPackageDetection  ,
detectionCorrection   
)

Test to check if a slanted QR code is properly detected.

Parameters
[in]TESTSuite
[in]test
Returns
none
125  {
126  ros::NodeHandle nh;
127  image_transport::ImageTransport it(nh);
128  // Advertise a known image on camera/rgb/image_raw topic
129  image_transport::Publisher pub = it.advertise("camera/rgb/image_raw", 1);
130  std::string fileLocation =
131  ros::package::getPath("package_identification_using_turtlebot") +
132  "/data/pack3_slant.png";
133  cv::Mat image = cv::imread(fileLocation);
134  cv::waitKey(3);
135  sensor_msgs::ImagePtr msg =
136  cv_bridge::CvImage(std_msgs::Header(), "bgr8", image).toImageMsg();
137  ros::Rate loop_rate(5);
138  PathPlanner planner({{-2.0, -3.0, 0.0, 1.0}, {-1.0, -2.0, 0.0, 1.0}});
139  ros::Time start_time = ros::Time::now();
140  ros::Duration timeout(15.0);
141  std::string result;
142  // If the test is not completed within timeout the test fails
143  while (ros::Time::now() - start_time < timeout) {
144  pub.publish(msg);
145  std::string incorrectDetection = "hello";
146  result = planner.waitPackageDetection(incorrectDetection);
147  if (result.substr(0, 4) == "pack") break;
148  loop_rate.sleep();
149  }
150  ASSERT_STREQ("pack#3", result.c_str());
151 }
Class PathPlanner has methods send goal points and initial pose of the turtlebot to move_base package...
Definition: PathPlanner.hpp:56
std::shared_ptr< ros::NodeHandle > nh
Definition: main.cpp:43
void testCb ( const geometry_msgs::PoseWithCovarianceStamped  msg)
49 {}