Skip to content

Commit

Permalink
Added new images for test.
Browse files Browse the repository at this point in the history
  • Loading branch information
mbjelonic committed May 9, 2018
1 parent c61f8ec commit b195a37
Show file tree
Hide file tree
Showing 4 changed files with 58 additions and 14 deletions.
3 changes: 1 addition & 2 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@ The YOLO packages have been tested under ROS Kinetic and Ubuntu 16.04. This is r
**Affiliation: Robotic Systems Lab, ETH Zurich**

![Darknet Ros example: Detection image](darknet_ros/doc/test_detection.png)
![Darknet Ros example: Detection image](darknet_ros/doc/quadruped_anymal_and_person_detection.png)

## Citing

Expand All @@ -31,8 +32,6 @@ This software is built on the Robotic Operating System ([ROS]), which needs to b

In order to install darknet_ros, clone the latest version using SSH (see [how to set up an SSH key](https://confluence.atlassian.com/bitbucket/set-up-an-ssh-key-728138079.html)) from this repository into your catkin workspace and compile the package using ROS.



cd catkin_workspace/src
git clone --recursive [email protected]:leggedrobotics/darknet_ros.git
cd ../
Expand Down
Binary file added darknet_ros/doc/quadruped_anymal_and_person.JPG
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
69 changes: 57 additions & 12 deletions darknet_ros/test/ObjectDetection.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@

// ROS
#include <ros/ros.h>
#include <ros/package.h>
#include <sensor_msgs/Image.h>
#include <actionlib/client/simple_action_client.h>

Expand Down Expand Up @@ -55,7 +56,7 @@ void checkForObjectsResultCB(
boundingBoxesResults_ = result->bounding_boxes;
}

bool sendImageToYolo(ros::NodeHandle nh, std::string imageName) {
bool sendImageToYolo(ros::NodeHandle nh, const std::string& pathToTestImage) {
//!Check for objects action client.
CheckForObjectsActionClientPtr checkForObjectsActionClient;

Expand All @@ -73,12 +74,6 @@ bool sendImageToYolo(ros::NodeHandle nh, std::string imageName) {
return false;
}

// Path to test image.
std::string pathToTestImage = darknetFilePath_;
pathToTestImage += "/data/";
pathToTestImage += imageName;
pathToTestImage += ".jpg";

// Get test image
cv_bridge::CvImagePtr cv_ptr(new cv_bridge::CvImage);
cv_ptr->image = cv::imread(pathToTestImage, CV_LOAD_IMAGE_COLOR);
Expand Down Expand Up @@ -106,14 +101,20 @@ bool sendImageToYolo(ros::NodeHandle nh, std::string imageName) {
return true;
}

TEST(ObjectDetection, DetectDog)
TEST(ObjectDetection, DISABLED_DetectDog)
{
srand((unsigned int) time(0));
ros::NodeHandle nodeHandle("~");

// Path to test image.
std::string pathToTestImage = darknetFilePath_;
pathToTestImage += "/data/";
pathToTestImage += "dog";
pathToTestImage += ".jpg";

// Send dog image to yolo.
ASSERT_TRUE(sendImageToYolo(nodeHandle, "dog"));
ASSERT_TRUE(sendImageToYolo(nodeHandle, "dog"));
ASSERT_TRUE(sendImageToYolo(nodeHandle, pathToTestImage));
ASSERT_TRUE(sendImageToYolo(nodeHandle, pathToTestImage));

// Evaluate if yolo was able to detect the three objects: dog, bicycle and car.
bool detectedDog = false;
Expand Down Expand Up @@ -154,12 +155,56 @@ TEST(ObjectDetection, DetectDog)
EXPECT_LT(centerErrorCar, 40.0);
}

TEST(ObjectDetection, DetectANYmal)
{
srand((unsigned int) time(0));
ros::NodeHandle nodeHandle("~");

// Path to test image.
std::string pathToTestImage = ros::package::getPath("darknet_ros");
pathToTestImage += "/doc/";
pathToTestImage += "quadruped_anymal_and_person";
pathToTestImage += ".JPG";

// Send dog image to yolo.
ASSERT_TRUE(sendImageToYolo(nodeHandle, pathToTestImage));
ASSERT_TRUE(sendImageToYolo(nodeHandle, pathToTestImage));

// Evaluate if yolo was able to detect the three objects: dog, bicycle and car.
bool detectedPerson = false;
double centerErrorPersonX;
double centerErrorPersonY;

for(unsigned int i = 0; i < boundingBoxesResults_.bounding_boxes.size(); ++i) {
double xPosCenter = boundingBoxesResults_.bounding_boxes.at(i).xmin +
(boundingBoxesResults_.bounding_boxes.at(i).xmax - boundingBoxesResults_.bounding_boxes.at(i).xmin)*0.5;
double yPosCenter = boundingBoxesResults_.bounding_boxes.at(i).ymin +
(boundingBoxesResults_.bounding_boxes.at(i).ymax - boundingBoxesResults_.bounding_boxes.at(i).ymin)*0.5;

if(boundingBoxesResults_.bounding_boxes.at(i).Class == "person") {
detectedPerson = true;
centerErrorPersonX = std::sqrt(std::pow(xPosCenter - 1650.0, 2));
centerErrorPersonY = std::sqrt(std::pow(xPosCenter - 1675.0, 2));
}
}

ASSERT_TRUE(detectedPerson);
EXPECT_LT(centerErrorPersonX, 30);
EXPECT_LT(centerErrorPersonY, 30);
}

TEST(ObjectDetection, DISABLED_DetectPerson) {
srand((unsigned int) time(0));
ros::NodeHandle nodeHandle("~");

ASSERT_TRUE(sendImageToYolo(nodeHandle, "person"));
ASSERT_TRUE(sendImageToYolo(nodeHandle, "person"));
// Path to test image.
std::string pathToTestImage = darknetFilePath_;
pathToTestImage += "/data/";
pathToTestImage += "person";
pathToTestImage += ".jpg";

ASSERT_TRUE(sendImageToYolo(nodeHandle, pathToTestImage));
ASSERT_TRUE(sendImageToYolo(nodeHandle, pathToTestImage));

// Evaluate if yolo was able to detect the person.
bool detectedPerson = false;
Expand Down

0 comments on commit b195a37

Please sign in to comment.