image_classification.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/ClassifyObject.h>
25 #include <opencv2/highgui/highgui.hpp>
26 #include <opencv2/imgproc/imgproc.hpp>
27 #include <ros/ros.h>
28 
29 #define LINESPACING 30
30 #define MOVEWINDOW 1000
31 #define DEFAULT_PARALLEL_SIZE 1
32 #define DEFAULT_IMAGE_BASE_PATH "/opt/movidius/ncappzoo/data/images/"
33 #define DEFAULT_DEMO_MODE 0
34 #define DEFAULT_PARALLEL_FLAG 1
35 
36 std::vector<std::string> getImagePath(std::string image_dir)
37 {
38  if (image_dir.back() != '/')
39  {
40  image_dir += "/";
41  }
42 
43  std::vector<std::string> files;
44 
45  DIR* dir;
46  struct dirent* ptr;
47 
48  if ((dir = opendir(image_dir.c_str())) == NULL)
49  {
50  std::cerr << "Open Dir error..." << std::endl;
51  exit(1);
52  }
53 
54  while ((ptr = readdir(dir)) != NULL)
55  {
56  if (strcmp(ptr->d_name, ".") == 0 || strcmp(ptr->d_name, "..") == 0)
57  continue;
58  else if (ptr->d_type == DT_REG)
59  files.push_back(image_dir + ptr->d_name);
60  }
61  closedir(dir);
62 
63  return files;
64 }
65 
66 int main(int argc, char** argv)
67 {
68  ros::init(argc, argv, "movidius_ncs_example_classification");
69  ros::NodeHandle n("~");
70  ros::ServiceClient client;
71 
72  std::string image_base_path = DEFAULT_IMAGE_BASE_PATH;
73  if (!n.getParam("image_base_path", image_base_path))
74  {
75  ROS_WARN("param image_base_path not set, use default");
76  }
77  ROS_INFO_STREAM("use image_base_path = " << image_base_path);
78  std::vector<std::string> image_paths = getImagePath(image_base_path);
79 
80  int parallel_size = DEFAULT_PARALLEL_SIZE;
81  if (!n.getParam("parallel_size", parallel_size))
82  {
83  ROS_WARN("param parallel_size not set, use default");
84  }
85  ROS_INFO_STREAM("use parallel_size = " << parallel_size);
86 
87  int demo_mode = DEFAULT_DEMO_MODE;
88  if (!n.getParam("demo_mode", demo_mode))
89  {
90  ROS_WARN("param demo_mode not set, use default");
91  }
92  ROS_INFO_STREAM("use demo_mode = " << demo_mode);
93 
94  int parallel_flag = DEFAULT_PARALLEL_FLAG;
95  if (!n.getParam("parallel_flag", parallel_flag))
96  {
97  ROS_WARN("param parallel_flag not set, use default");
98  }
99  ROS_INFO_STREAM("use parallel_flag = " << parallel_flag);
100 
101  if (parallel_flag == 0)
102  {
103  client = n.serviceClient<object_msgs::ClassifyObject>("/movidius_ncs_image_single/classify_object");
104  }
105  else
106  {
107  client = n.serviceClient<object_msgs::ClassifyObject>("/movidius_ncs_image_multiple/classify_object");
108  }
109 
110  if (demo_mode == 0)
111  {
112  object_msgs::ClassifyObject srv;
113  srv.request.image_paths = image_paths;
114  boost::posix_time::ptime start = boost::posix_time::microsec_clock::local_time();
115  if (!client.call(srv))
116  {
117  ROS_ERROR("failed to call service ClassifyObject");
118  return 1;
119  }
120  boost::posix_time::ptime end = boost::posix_time::microsec_clock::local_time();
121  boost::posix_time::time_duration msdiff = end - start;
122 
123  for (unsigned int i = 0; i < srv.response.objects.size(); i++)
124  {
125  cv_bridge::CvImage cv_image;
126  cv_image.image = cv::imread(image_paths[i]);
127  cv_image.encoding = "bgr8";
128  int cnt = 0;
129 
130  ROS_INFO("Classification 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_name << ": "
135  << srv.response.objects[i].objects_vector[j].probability * 100 << "%";
136 
137  ROS_INFO("%d: object: %s\nprobability: %lf%%", j, srv.response.objects[i].objects_vector[j].object_name.c_str(),
138  srv.response.objects[i].objects_vector[j].probability * 100);
139 
140  cv::putText(cv_image.image, ss.str(), cvPoint(LINESPACING, LINESPACING * (++cnt)), cv::FONT_HERSHEY_SIMPLEX,
141  0.5, cv::Scalar(0, 255, 0), 1);
142  }
143 
144  cv::imshow("image_classification", cv_image.image);
145  cv::waitKey(0);
146  }
147  ROS_INFO("inference %lu images during %ld ms", srv.response.objects.size(), msdiff.total_milliseconds());
148  }
149  else
150  {
151  while (1)
152  {
153  object_msgs::ClassifyObject srv;
154  std::vector<int> random_index_list;
155  for (int i = 0; i < parallel_size; i++)
156  {
157  std::random_device rd;
158  std::default_random_engine engine(rd());
159  std::uniform_int_distribution<> dis(0, image_paths.size() - 1);
160  auto dice = std::bind(dis, engine);
161  int random_index = dice();
162  random_index_list.push_back(random_index);
163  srv.request.image_paths.push_back(image_paths[random_index]);
164  }
165 
166  if (!client.call(srv))
167  {
168  ROS_ERROR("failed to call service ClassifyObject");
169  exit(1);
170  }
171 
172  for (unsigned int i = 0; i < srv.response.objects.size(); i++)
173  {
174  cv_bridge::CvImage cv_image;
175  cv_image.image = cv::imread(image_paths[random_index_list[i]]);
176  cv_image.encoding = "bgr8";
177  int cnt = 0;
178 
179  for (unsigned int j = 0; j < srv.response.objects[i].objects_vector.size(); j++)
180  {
181  std::stringstream ss;
182  ss << srv.response.objects[i].objects_vector[j].object_name << ": "
183  << srv.response.objects[i].objects_vector[j].probability * 100 << "%";
184 
185  cv::putText(cv_image.image, ss.str(), cvPoint(LINESPACING, LINESPACING * (++cnt)), cv::FONT_HERSHEY_SIMPLEX,
186  0.5, cv::Scalar(0, 255, 0), 1);
187  }
188 
189  if (parallel_flag == 0)
190  {
191  cv::imshow("image classification with single device", cv_image.image);
192  cv::waitKey(20);
193  }
194  else
195  {
196  cv::namedWindow("image classification with multiple devices");
197  cv::moveWindow("image classification with multiple devices", MOVEWINDOW, 0);
198  cv::imshow("image classification with multiple devices", cv_image.image);
199  cv::waitKey(20);
200  }
201  }
202  }
203  }
204 
205  return 0;
206 }
#define DEFAULT_PARALLEL_FLAG
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
ROSCPP_DECL void start()
#define DEFAULT_IMAGE_BASE_PATH
#define LINESPACING
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)
#define ROS_WARN(...)
#define DEFAULT_DEMO_MODE
#define MOVEWINDOW
#define ROS_INFO(...)
std::vector< std::string > getImagePath(std::string image_dir)
#define ROS_INFO_STREAM(args)
#define DEFAULT_PARALLEL_SIZE
bool getParam(const std::string &key, std::string &s) const
#define ROS_ERROR(...)
int main(int argc, char **argv)


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