dnn_images_test.cpp
Go to the documentation of this file.
1 #include <gtest/gtest.h>
2 
3 #include <ros/ros.h>
5 #include <opencv2/highgui/highgui.hpp>
6 #include <cv_bridge/cv_bridge.h>
7 
8 #include "dnn_detect/DetectedObject.h"
9 #include "dnn_detect/DetectedObjectArray.h"
10 #include "dnn_detect/Detect.h"
11 
12 #include <boost/thread/thread.hpp>
13 
14 #if CV_MAJOR_VERSION < 4
15  #define IMREAD_COLOR_MODE CV_LOAD_IMAGE_COLOR
16 #else
17  #define IMREAD_COLOR_MODE cv::IMREAD_COLOR
18 #endif
19 
20 class DnnImagesTest : public ::testing::Test {
21 protected:
22  virtual void SetUp() {
24  image_pub = it->advertise("camera/image", 1);
25 
26  ros::NodeHandle nh_priv("~");
27  nh_priv.getParam("image_directory", image_directory);
28  object_sub = nh.subscribe("/dnn_objects", 1, &DnnImagesTest::object_callback, this);
29  got_object = false;
30  got_cat = false;
31 
32  }
33 
34  // Make a service request to trigger detection
35  void trigger() {
36  ros::NodeHandle node;
37  ros::ServiceClient client =
38  node.serviceClient<dnn_detect::Detect>("/dnn_detect/detect");
39  dnn_detect::Detect d;
40  client.call(d);
41  }
42 
43  virtual void TearDown() { delete it;}
44 
45  void publish_image(std::string file) {
46  boost::thread trig(&DnnImagesTest::trigger, this);
47 
48  sleep(1);
49  cv::Mat image = cv::imread(image_directory+file, IMREAD_COLOR_MODE);
50  sensor_msgs::ImagePtr msg = cv_bridge::CvImage(std_msgs::Header(), "bgr8",
51  image).toImageMsg();
52  image_pub.publish(msg);
53  }
54 
56 
57  // Set up Publishing of static images
60 
61  bool got_object;
62  bool got_cat;
64 
65  std::string image_directory;
66 
67  // Set up subscribing
68  void object_callback(const dnn_detect::DetectedObjectArray& results) {
69  got_object = true;
70  for (const auto& obj : results.objects) {
71  if (obj.class_name == "cat") {
72  got_cat = true;
73  }
74  }
75  }
76 };
77 
78 
80  ros::Rate loop_rate(5);
81  while (nh.ok() && !got_object && !got_cat) {
82  publish_image("cat.jpg");
83  ros::spinOnce();
84  loop_rate.sleep();
85  }
86 
87  ASSERT_TRUE(got_cat);
88 }
89 
90 int main(int argc, char** argv)
91 {
92 
93  testing::InitGoogleTest(&argc, argv);
94  ros::init(argc, argv, "DnnImagesTest");
95  return RUN_ALL_TESTS();
96 }
d
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
void publish_image(std::string file)
std::string image_directory
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
image_transport::Publisher image_pub
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
bool call(MReq &req, MRes &res)
void object_callback(const dnn_detect::DetectedObjectArray &results)
int main(int argc, char **argv)
ros::Subscriber object_sub
virtual void TearDown()
void publish(const sensor_msgs::Image &message) const
ros::NodeHandle nh
#define IMREAD_COLOR_MODE
virtual void SetUp()
image_transport::ImageTransport * it
bool sleep()
TEST_F(DnnImagesTest, cat)
bool getParam(const std::string &key, std::string &s) const
bool ok() const
ROSCPP_DECL void spinOnce()
sensor_msgs::ImagePtr toImageMsg() const


dnn_detect
Author(s): Jim Vaughan
autogenerated on Thu Sep 24 2020 03:23:11