10 #include <gtest/gtest.h>
16 #include <sensor_msgs/Image.h>
19 #include <boost/thread.hpp>
23 #include <opencv2/core/core.hpp>
24 #include <opencv2/highgui/highgui.hpp>
25 #include <opencv2/imgproc/imgproc.hpp>
28 #include <darknet_ros_msgs/CheckForObjectsAction.h>
37 #ifdef DARKNET_FILE_PATH
38 std::string darknetFilePath_ = DARKNET_FILE_PATH;
40 #error Path of darknet repository is not defined in CMakeLists.txt.
51 std::cout <<
"[ObjectDetectionTest] Received bounding boxes." << std::endl;
61 std::string checkForObjectsActionName;
62 nh.
param(
"/darknet_ros/camera_action", checkForObjectsActionName, std::string(
"/darknet_ros/check_for_objects"));
66 if (!checkForObjectsActionClient->waitForServer(
ros::Duration(20.0))) {
67 std::cout <<
"[ObjectDetectionTest] sendImageToYolo(): checkForObjects action server has not been advertised." << std::endl;
73 cv_ptr->image = cv::imread(pathToTestImage, cv::IMREAD_COLOR);
75 sensor_msgs::ImagePtr image = cv_ptr->toImageMsg();
78 darknet_ros_msgs::CheckForObjectsGoal goal;
87 if (!checkForObjectsActionClient->waitForResult(
ros::Duration(100.0))) {
88 std::cout <<
"[ObjectDetectionTest] sendImageToYolo(): checkForObjects action server took to long to send back result." << std::endl;
92 std::cout <<
"[ObjectDetectionTest] Object detection for one image took " << endYolo - beginYolo <<
" seconds." << std::endl;
96 TEST(ObjectDetection, DISABLED_DetectDog) {
97 srand(
static_cast<unsigned int>(time(
nullptr)));
101 std::string pathToTestImage = darknetFilePath_;
102 pathToTestImage +=
"/data/";
103 pathToTestImage +=
"dog";
104 pathToTestImage +=
".jpg";
111 bool detectedDog =
false;
112 double centerErrorDog;
113 bool detectedBicycle =
false;
114 double centerErrorBicycle;
115 bool detectedCar =
false;
116 double centerErrorCar;
119 double xPosCenter = boundingBox.xmin + (boundingBox.xmax - boundingBox.xmin) * 0.5;
120 double yPosCenter = boundingBox.ymin + (boundingBox.ymax - boundingBox.ymin) * 0.5;
122 if (boundingBox.Class ==
"dog") {
125 centerErrorDog = std::sqrt(std::pow(xPosCenter - 222.5, 2) + std::pow(yPosCenter - 361.5, 2));
127 if (boundingBox.Class ==
"bicycle") {
128 detectedBicycle =
true;
130 centerErrorBicycle = std::sqrt(std::pow(xPosCenter - 338.0, 2) + std::pow(yPosCenter - 289.0, 2));
132 if (boundingBox.Class ==
"truck") {
135 centerErrorCar = std::sqrt(std::pow(xPosCenter - 561.0, 2) + std::pow(yPosCenter - 126.5, 2));
139 ASSERT_TRUE(detectedDog);
140 EXPECT_LT(centerErrorDog, 40.0);
141 ASSERT_TRUE(detectedBicycle);
142 EXPECT_LT(centerErrorBicycle, 40.0);
143 ASSERT_TRUE(detectedCar);
144 EXPECT_LT(centerErrorCar, 40.0);
147 TEST(ObjectDetection, DetectANYmal) {
148 srand(
static_cast<unsigned int>(time(
nullptr)));
153 pathToTestImage +=
"/doc/";
154 pathToTestImage +=
"quadruped_anymal_and_person";
155 pathToTestImage +=
".JPG";
163 bool detectedPerson =
false;
164 double centerErrorPersonX;
165 double centerErrorPersonY;
168 double xPosCenter = boundingBox.xmin + (boundingBox.xmax - boundingBox.xmin) * 0.5;
169 double yPosCenter = boundingBox.ymin + (boundingBox.ymax - boundingBox.ymin) * 0.5;
171 if (boundingBox.Class ==
"person") {
172 detectedPerson =
true;
173 centerErrorPersonX = std::sqrt(std::pow(xPosCenter - 1650.0, 2));
174 centerErrorPersonY = std::sqrt(std::pow(xPosCenter - 1675.0, 2));
178 ASSERT_TRUE(detectedPerson);
179 EXPECT_LT(centerErrorPersonX, 30);
180 EXPECT_LT(centerErrorPersonY, 30);
183 TEST(ObjectDetection, DISABLED_DetectPerson) {
184 srand(
static_cast<unsigned int>(time(
nullptr)));
188 std::string pathToTestImage = darknetFilePath_;
189 pathToTestImage +=
"/data/";
190 pathToTestImage +=
"person";
191 pathToTestImage +=
".jpg";
197 bool detectedPerson =
false;
198 double centerErrorPerson;
201 double xPosCenter = boundingBox.xmin + (boundingBox.xmax - boundingBox.xmin) * 0.5;
202 double yPosCenter = boundingBox.ymin + (boundingBox.ymax - boundingBox.ymin) * 0.5;
204 if (boundingBox.Class ==
"person") {
205 detectedPerson =
true;
207 centerErrorPerson = std::sqrt(std::pow(xPosCenter - 228.0, 2) + std::pow(yPosCenter - 238.0, 2));
211 ASSERT_TRUE(detectedPerson);
212 EXPECT_LT(centerErrorPerson, 40.0);