ncs_manager.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 <string>
18 #include <vector>
19 
20 #include <image_transport/image_transport.h>
22 
23 namespace movidius_ncs_lib
24 {
25 NCSManager::NCSManager(const int& max_device_number, const int& start_device_index, const Device::LogLevel& log_level,
26  const std::string& cnn_type, const std::string& graph_file_path,
27  const std::string& category_file_path, const int& network_dimension,
28  const std::vector<float>& mean, const float& scale, const int& top_n)
29  : max_device_number_(max_device_number)
30  , start_device_index_(start_device_index)
31  , log_level_(log_level)
32  , cnn_type_(cnn_type)
33  , graph_file_path_(graph_file_path)
34  , category_file_path_(category_file_path)
35  , network_dimension_(network_dimension)
36  , mean_(mean)
37  , scale_(scale)
38  , top_n_(top_n)
39  , user_param_(nullptr)
40  , device_count_(0)
41 {
43 }
44 
46 {
47 }
48 
50 {
51  char device_name[MVNC_MAX_NAME_SIZE];
52  while (mvncGetDeviceName(device_count_, device_name, sizeof(device_name)) != MVNC_DEVICE_NOT_FOUND)
53  {
54  device_count_++;
55 
57  {
58  break;
59  }
60  }
61 
63 
64  for (int device_index = start_device_index_; device_index < device_count_; device_index++)
65  {
66  auto ncs_handle = std::make_shared<movidius_ncs_lib::NCS>(device_index, static_cast<Device::LogLevel>(log_level_),
69  ncs_handle_list_.push_back(ncs_handle);
70  }
71 }
72 
73 void join(std::thread& t)
74 {
75  t.join();
76 }
77 
78 void NCSManager::deviceThread(int device_index)
79 {
80  while (1)
81  {
82  if (!image_list_.empty())
83  {
84  mtx_.lock();
85  auto first_image = image_list_[0].image;
86  auto first_image_header = image_list_[0].header;
87  if (!image_list_.empty())
88  {
89  image_list_.erase(image_list_.begin());
90  }
91  else
92  {
93  mtx_.unlock();
94  continue;
95  }
96  mtx_.unlock();
97 
98  if (!cnn_type_.compare("alexnet") || !cnn_type_.compare("googlenet") || !cnn_type_.compare("inception_v1") ||
99  !cnn_type_.compare("inception_v2") || !cnn_type_.compare("inception_v3") ||
100  !cnn_type_.compare("inception_v4") || !cnn_type_.compare("mobilenet") || !cnn_type_.compare("squeezenet"))
101  {
102  ncs_handle_list_[device_index]->loadTensor(first_image);
103  ncs_handle_list_[device_index]->classify();
104  ClassificationResultPtr result = ncs_handle_list_[device_index]->getClassificationResult();
105 
106  p_c_(result, first_image_header);
107  }
108  else
109  {
110  ncs_handle_list_[device_index]->loadTensor(first_image);
111  ncs_handle_list_[device_index]->detect();
112  DetectionResultPtr result = ncs_handle_list_[device_index]->getDetectionResult();
113 
114  p_d_(result, first_image_header);
115  }
116  }
117  else
118  {
119  usleep(1);
120  }
121  }
122 }
123 
125 {
126  for (int i = 0; i < device_count_ - start_device_index_; i++)
127  {
128  threads_.push_back(std::thread(&NCSManager::deviceThread, this, i));
129  }
130 
131  std::for_each(threads_.begin(), threads_.end(), join);
132 
133  ROS_INFO("started %d threads", device_count_ - start_device_index_);
134 }
135 
136 std::vector<ClassificationResultPtr> NCSManager::classifyImage(const std::vector<std::string>& images)
137 {
138  int image_size = static_cast<int>(images.size());
139  std::vector<ClassificationResultPtr> results(image_size);
140 
141  int parallel_group = image_size / (device_count_ - start_device_index_);
142  int parallel_left = image_size % (device_count_ - start_device_index_);
143 
144  for (int i = 0; i < parallel_group; i++)
145  {
146 #pragma omp parallel for
147  for (int device_index = 0; device_index < device_count_ - start_device_index_; device_index++)
148  {
149  cv::Mat imageData = cv::imread(images[i * (device_count_ - start_device_index_) + device_index]);
150  ncs_handle_list_[device_index]->loadTensor(imageData);
151  ncs_handle_list_[device_index]->classify();
152  ClassificationResultPtr result = ncs_handle_list_[device_index]->getClassificationResult();
153  results[i * (device_count_ - start_device_index_) + device_index] =
154  std::make_shared<ClassificationResult>(*result);
155  }
156  }
157 
158  for (int j = 0; j < parallel_left; j++)
159  {
160  cv::Mat imageData = cv::imread(images[parallel_group * (device_count_ - start_device_index_) + j]);
161  ncs_handle_list_[j]->loadTensor(imageData);
162  ncs_handle_list_[j]->classify();
163  ClassificationResultPtr result = ncs_handle_list_[j]->getClassificationResult();
164  results[parallel_group * (device_count_ - start_device_index_) + j] =
165  std::make_shared<ClassificationResult>(*result);
166  }
167 
168  return results;
169 }
170 
171 std::vector<DetectionResultPtr> NCSManager::detectImage(const std::vector<std::string>& images)
172 {
173  int image_size = static_cast<int>(images.size());
174  std::vector<DetectionResultPtr> results(image_size);
175 
176  int parallel_group = image_size / (device_count_ - start_device_index_);
177  int parallel_left = image_size % (device_count_ - start_device_index_);
178 
179  for (int i = 0; i < parallel_group; i++)
180  {
181 #pragma omp parallel for
182  for (int device_index = 0; device_index < device_count_ - start_device_index_; device_index++)
183  {
184  cv::Mat imageData = cv::imread(images[i * (device_count_ - start_device_index_) + device_index]);
185  ncs_handle_list_[device_index]->loadTensor(imageData);
186  ncs_handle_list_[device_index]->detect();
187  DetectionResultPtr result = ncs_handle_list_[device_index]->getDetectionResult();
188  results[i * (device_count_ - start_device_index_) + device_index] = std::make_shared<DetectionResult>(*result);
189  }
190  }
191 
192  for (int i = 0; i < parallel_left; i++)
193  {
194  cv::Mat imageData = cv::imread(images[parallel_group * (device_count_ - start_device_index_) + i]);
195  ncs_handle_list_[i]->loadTensor(imageData);
196  ncs_handle_list_[i]->detect();
197  DetectionResultPtr result = ncs_handle_list_[i]->getDetectionResult();
198  results[parallel_group * (device_count_ - start_device_index_) + i] = std::make_shared<DetectionResult>(*result);
199  }
200 
201  return results;
202 }
203 
204 void NCSManager::classifyStream(const cv::Mat& image, FUNP_C cbGetClassificationResult,
205  const sensor_msgs::ImageConstPtr& image_msg)
206 {
207  p_c_ = cbGetClassificationResult;
208 
209  ImageFrame imageFrame;
210  imageFrame.header = image_msg->header;
211  imageFrame.image = image;
212 
213  mtx_.lock();
214  if (image_list_.size() > IMAGE_BUFFER_SIZE)
215  {
216  image_list_.erase(image_list_.begin());
217  }
218  image_list_.push_back(imageFrame);
219  mtx_.unlock();
220 }
221 
222 void NCSManager::detectStream(const cv::Mat& image, FUNP_D cbGetDetectionResult,
223  const sensor_msgs::ImageConstPtr& image_msg)
224 {
225  p_d_ = cbGetDetectionResult;
226 
227  ImageFrame imageFrame;
228  imageFrame.header = image_msg->header;
229  imageFrame.image = image;
230 
231  mtx_.lock();
232  if (image_list_.size() > IMAGE_BUFFER_SIZE)
233  {
234  image_list_.erase(image_list_.begin());
235  }
236  image_list_.push_back(imageFrame);
237  mtx_.unlock();
238 }
239 } // namespace movidius_ncs_lib
NCSManager(const int &max_device_number, const int &device_index, const Device::LogLevel &log_level, const std::string &cnn_type, const std::string &graph_file_path, const std::string &category_file_path, const int &network_dimension, const std::vector< float > &mean, const float &scale, const int &top_n)
Definition: ncs_manager.cpp:25
std::vector< DetectionResultPtr > detectImage(const std::vector< std::string > &images)
std::shared_ptr< DetectionResult > DetectionResultPtr
Definition: result.h:64
const std::vector< float > mean_
Definition: ncs_manager.h:74
boost::function< void(DetectionResultPtr result, std_msgs::Header header)> FUNP_D
Definition: ncs_manager.h:38
std::vector< std::shared_ptr< movidius_ncs_lib::NCS > > ncs_handle_list_
Definition: ncs_manager.h:79
void deviceThread(int device_index)
Definition: ncs_manager.cpp:78
void classifyStream(const cv::Mat &image, FUNP_C cbGetClassificationResult, const sensor_msgs::ImageConstPtr &image_msg)
std::vector< std::thread > threads_
Definition: ncs_manager.h:87
const Device::LogLevel log_level_
Definition: ncs_manager.h:69
boost::function< void(ClassificationResultPtr result, std_msgs::Header header)> FUNP_C
Definition: ncs_manager.h:37
#define ROS_INFO(...)
std::vector< ClassificationResultPtr > classifyImage(const std::vector< std::string > &images)
void detectStream(const cv::Mat &image, FUNP_D cbGetDetectionResult, const sensor_msgs::ImageConstPtr &image_msg)
std::vector< ImageFrame > image_list_
Definition: ncs_manager.h:85
const std::string cnn_type_
Definition: ncs_manager.h:70
void join(std::thread &t)
Definition: ncs_manager.cpp:73
std::shared_ptr< ClassificationResult > ClassificationResultPtr
Definition: result.h:63
std_msgs::Header header
Definition: ncs_manager.h:43
const std::string category_file_path_
Definition: ncs_manager.h:72
const std::string graph_file_path_
Definition: ncs_manager.h:71
#define IMAGE_BUFFER_SIZE
Definition: ncs_manager.h:33


movidius_ncs_lib
Author(s): Xiaojun Huang
autogenerated on Mon Jun 10 2019 14:11:23