image_detection.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2017 Intel Corporation
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 #include <dirent.h>
18 #include <random>
19 #include <string>
20 #include <vector>
21 
22 #include <boost/date_time/posix_time/posix_time.hpp>
23 #include <cv_bridge/cv_bridge.h>
24 #include <object_msgs/DetectObject.h>
25 #include <opencv2/highgui/highgui.hpp>
26 #include <opencv2/imgproc/imgproc.hpp>
27 #include <ros/ros.h>
28 
29 #define MOVEWINDOW 1000
30 #define DEFAULT_PARALLEL_SIZE 1
31 #define DEFAULT_IMAGE_BASE_PATH "/opt/movidius/ncappzoo/data/images/"
32 #define DEFAULT_DEMO_MODE 0
33 #define DEFAULT_PARALLEL_FLAG 1
34 
35 std::vector<std::string> getImagePath(std::string image_dir)
36 {
37  if (image_dir.back() != '/')
38  {
39  image_dir += "/";
40  }
41 
42  std::vector<std::string> files;
43 
44  DIR* dir;
45  struct dirent* ptr;
46 
47  if ((dir = opendir(image_dir.c_str())) == NULL)
48  {
49  std::cerr << "Open Dir error..." << std::endl;
50  exit(1);
51  }
52 
53  while ((ptr = readdir(dir)) != NULL)
54  {
55  if (strcmp(ptr->d_name, ".") == 0 || strcmp(ptr->d_name, "..") == 0)
56  continue;
57  else if (ptr->d_type == DT_REG)
58  files.push_back(image_dir + ptr->d_name);
59  }
60  closedir(dir);
61 
62  return files;
63 }
64 
65 int main(int argc, char** argv)
66 {
67  ros::init(argc, argv, "movidius_ncs_example_detection");
68  ros::NodeHandle n("~");
69  ros::ServiceClient client;
70 
71  std::string image_base_path = DEFAULT_IMAGE_BASE_PATH;
72  if (!n.getParam("image_base_path", image_base_path))
73  {
74  ROS_WARN("param image_base_path not set, use default");
75  }
76  ROS_INFO_STREAM("use image_base_path = " << image_base_path);
77  std::vector<std::string> image_paths = getImagePath(image_base_path);
78 
79  int parallel_size = DEFAULT_PARALLEL_SIZE;
80  if (!n.getParam("parallel_size", parallel_size))
81  {
82  ROS_WARN("param parallel_size not set, use default");
83  }
84  ROS_INFO_STREAM("use parallel_size = " << parallel_size);
85 
86  int demo_mode = DEFAULT_DEMO_MODE;
87  if (!n.getParam("demo_mode", demo_mode))
88  {
89  ROS_WARN("param demo_mode not set, use default");
90  }
91  ROS_INFO_STREAM("use demo_mode = " << demo_mode);
92 
93  int parallel_flag = DEFAULT_PARALLEL_FLAG;
94  if (!n.getParam("parallel_flag", parallel_flag))
95  {
96  ROS_WARN("param parallel_flag not set, use default");
97  }
98  ROS_INFO_STREAM("use parallel_flag = " << parallel_flag);
99 
100  if (parallel_flag == 0)
101  {
102  client = n.serviceClient<object_msgs::DetectObject>("/movidius_ncs_image_single/detect_object");
103  }
104  else
105  {
106  client = n.serviceClient<object_msgs::DetectObject>("/movidius_ncs_image_multiple/detect_object");
107  }
108 
109  if (demo_mode == 0)
110  {
111  object_msgs::DetectObject srv;
112  srv.request.image_paths = image_paths;
113  boost::posix_time::ptime start = boost::posix_time::microsec_clock::local_time();
114  if (!client.call(srv))
115  {
116  ROS_ERROR("failed to call service DetectObject");
117  return 1;
118  }
119  boost::posix_time::ptime end = boost::posix_time::microsec_clock::local_time();
120  boost::posix_time::time_duration msdiff = end - start;
121 
122  for (unsigned int i = 0; i < srv.response.objects.size(); i++)
123  {
124  cv_bridge::CvImage cv_image;
125  cv_image.image = cv::imread(image_paths[i]);
126  cv_image.encoding = "bgr8";
127  int width = cv_image.image.cols;
128  int height = cv_image.image.rows;
129 
130  ROS_INFO("Detection result for image No.%u:", i + 1);
131  for (unsigned int j = 0; j < srv.response.objects[i].objects_vector.size(); j++)
132  {
133  std::stringstream ss;
134  ss << srv.response.objects[i].objects_vector[j].object.object_name << ": "
135  << srv.response.objects[i].objects_vector[j].object.probability * 100 << "%";
136 
137  ROS_INFO("%d: object: %s", j, srv.response.objects[i].objects_vector[j].object.object_name.c_str());
138  ROS_INFO("prob: %f", srv.response.objects[i].objects_vector[j].object.probability);
139  ROS_INFO("location: (%d, %d, %d, %d)", srv.response.objects[i].objects_vector[j].roi.x_offset,
140  srv.response.objects[i].objects_vector[j].roi.y_offset,
141  srv.response.objects[i].objects_vector[j].roi.width,
142  srv.response.objects[i].objects_vector[j].roi.height);
143 
144  int xmin = srv.response.objects[i].objects_vector[j].roi.x_offset;
145  int ymin = srv.response.objects[i].objects_vector[j].roi.y_offset;
146  int w = srv.response.objects[i].objects_vector[j].roi.width;
147  int h = srv.response.objects[i].objects_vector[j].roi.height;
148 
149  int xmax = ((xmin + w) < width) ? (xmin + w) : width;
150  int ymax = ((ymin + h) < height) ? (ymin + h) : height;
151 
152  cv::Point left_top = cv::Point(xmin, ymin);
153  cv::Point right_bottom = cv::Point(xmax, ymax);
154  cv::rectangle(cv_image.image, left_top, right_bottom, cv::Scalar(0, 255, 0), 1, cv::LINE_8, 0);
155  cv::rectangle(cv_image.image, cvPoint(xmin, ymin), cvPoint(xmax, ymin + 20), cv::Scalar(0, 255, 0), -1);
156  cv::putText(cv_image.image, ss.str(), cvPoint(xmin + 5, ymin + 20), cv::FONT_HERSHEY_PLAIN, 1,
157  cv::Scalar(0, 0, 255), 1);
158  }
159 
160  cv::imshow("image_detection", cv_image.image);
161  cv::waitKey(0);
162  }
163  ROS_INFO("inference %lu images during %ld ms", srv.response.objects.size(), msdiff.total_milliseconds());
164  }
165  else
166  {
167  while (1)
168  {
169  object_msgs::DetectObject srv;
170  std::vector<int> random_index_list;
171  for (int i = 0; i < parallel_size; i++)
172  {
173  std::random_device rd;
174  std::default_random_engine engine(rd());
175  std::uniform_int_distribution<> dis(0, image_paths.size() - 1);
176  auto dice = std::bind(dis, engine);
177  int random_index = dice();
178  random_index_list.push_back(random_index);
179  srv.request.image_paths.push_back(image_paths[random_index]);
180  }
181 
182  if (!client.call(srv))
183  {
184  ROS_ERROR("failed to call service DetectObject");
185  exit(1);
186  }
187 
188  for (unsigned int i = 0; i < srv.response.objects.size(); i++)
189  {
190  cv_bridge::CvImage cv_image;
191  cv_image.image = cv::imread(image_paths[random_index_list[i]]);
192  cv_image.encoding = "bgr8";
193  int width = cv_image.image.cols;
194  int height = cv_image.image.rows;
195 
196  for (unsigned int j = 0; j < srv.response.objects[i].objects_vector.size(); j++)
197  {
198  std::stringstream ss;
199  ss << srv.response.objects[i].objects_vector[j].object.object_name << ": "
200  << srv.response.objects[i].objects_vector[j].object.probability * 100 << "%";
201 
202  int xmin = srv.response.objects[i].objects_vector[j].roi.x_offset;
203  int ymin = srv.response.objects[i].objects_vector[j].roi.y_offset;
204  int w = srv.response.objects[i].objects_vector[j].roi.width;
205  int h = srv.response.objects[i].objects_vector[j].roi.height;
206 
207  int xmax = ((xmin + w) < width) ? (xmin + w) : width;
208  int ymax = ((ymin + h) < height) ? (ymin + h) : height;
209 
210  cv::Point left_top = cv::Point(xmin, ymin);
211  cv::Point right_bottom = cv::Point(xmax, ymax);
212  cv::rectangle(cv_image.image, left_top, right_bottom, cv::Scalar(0, 255, 0), 1, cv::LINE_8, 0);
213  cv::rectangle(cv_image.image, cvPoint(xmin, ymin), cvPoint(xmax, ymin + 20), cv::Scalar(0, 255, 0), -1);
214 
215  cv::putText(cv_image.image, ss.str(), cvPoint(xmin + 5, ymin + 20), cv::FONT_HERSHEY_PLAIN, 1,
216  cv::Scalar(0, 0, 255), 1);
217  }
218 
219  if (parallel_flag == 0)
220  {
221  cv::imshow("image detection with single device", cv_image.image);
222  cv::waitKey(1);
223  }
224  else
225  {
226  cv::namedWindow("image detection with multiple devices");
227  cv::moveWindow("image detection with multiple devices", MOVEWINDOW, 0);
228  cv::imshow("image detection with multiple devices", cv_image.image);
229  cv::waitKey(1);
230  }
231  }
232  }
233  }
234 
235  return 0;
236 }
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
std::vector< std::string > getImagePath(std::string image_dir)
ROSCPP_DECL void start()
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
std::string encoding
bool call(MReq &req, MRes &res)
int main(int argc, char **argv)
#define ROS_WARN(...)
#define ROS_INFO(...)
#define ROS_INFO_STREAM(args)
#define MOVEWINDOW
#define DEFAULT_PARALLEL_SIZE
bool getParam(const std::string &key, std::string &s) const
#define DEFAULT_IMAGE_BASE_PATH
#define DEFAULT_DEMO_MODE
#define ROS_ERROR(...)
#define DEFAULT_PARALLEL_FLAG


movidius_ncs_example
Author(s): Xiaojun Huang
autogenerated on Mon Jun 10 2019 14:11:21