ncs.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 <algorithm>
18 #include <string>
19 #include <utility>
20 #include <vector>
21 #include <fstream>
22 #include <streambuf>
23 #include <cerrno>
24 #include <boost/algorithm/string.hpp>
25 #include <boost/lexical_cast.hpp>
26 
29 #include "movidius_ncs_lib/ncs.h"
31 
32 namespace movidius_ncs_lib
33 {
34 NCS::NCS(int device_index,
35  Device::LogLevel log_level,
36  const std::string& cnn_type,
37  const std::string& graph_file_path,
38  const std::string& category_file_path,
39  const int network_dimension,
40  const std::vector<float>& mean,
41  const float& scale,
42  const int& top_n)
43  : device_(nullptr),
44  graph_(nullptr),
45  tensor_(nullptr),
46  device_index_(device_index),
47  log_level_(log_level),
48  cnn_type_(cnn_type),
49  network_dimension_(network_dimension),
50  mean_(mean),
51  scale_(scale),
52  top_n_(top_n),
53  user_param_(nullptr)
54 {
55  initDevice();
56  loadGraph(graph_file_path);
57  loadCategories(category_file_path);
58  tensor_ = std::make_shared<Tensor>(std::pair<int, int>(network_dimension_, network_dimension_),
59  mean_, scale_);
60  result_ = std::make_shared<Result>(cnn_type_);
61 }
62 
64 {
65 }
66 
68 {
69  assert(graph_->getHandle() != nullptr);
70  try
71  {
72  uint16_t* probabilities;
73  unsigned int length;
74  int ret = mvncGetResult(graph_->getHandle(), reinterpret_cast<void**>(&probabilities),
75  &length, &user_param_);
77  std::vector<uint16_t> result_vector(reinterpret_cast<uint16_t*>(probabilities),
78  reinterpret_cast<uint16_t*>(probabilities) + length);
79  ItemsPtr items = std::make_shared<Items>();
80  for (size_t index = 0; index < length / 2; ++index)
81  {
82  float fp32;
83 #ifdef SUPPORT_F16C
84  fp32 = _cvtsh_ss(probabilities[index]);
85 #else
86  Tensor::fp16tofp32(&fp32, probabilities[index]);
87 #endif
88  Item item;
89  item.category = categories_[index];
90  item.probability = fp32;
91  items->push_back(item);
92  }
93 
94  auto cmp = [](const Item & a, const Item & b)
95  {
96  return a.probability > b.probability;
97  };
98  std::sort(items->begin(), items->end(), cmp);
99 
100  if (!result_->getClassificationResult()->items.empty())
101  {
102  result_->getClassificationResult()->items.clear();
103  }
104 
105  for (auto i : *items)
106  {
107  result_->setClassificationResult(i);
108  if (static_cast<int>(result_->getClassificationResult()->items.size()) == top_n_)
109  {
110  break;
111  }
112  }
113  result_->setClassificationResult(graph_->getTimeTaken());
114  device_->monitorThermal();
115  }
116  catch (MvncMyriadError& e)
117  {
118  ROS_ERROR_STREAM(e.what());
119  std::string debug_info = graph_->getDebugInfo();
120  ROS_ERROR_STREAM("myriad debug info: " << debug_info);
121  }
122  catch (NCSException& e)
123  {
124  ROS_ERROR_STREAM(e.what());
125  }
126 }
127 
129 {
130  assert(graph_->getHandle() != nullptr);
131  try
132  {
133  uint16_t* result;
134  unsigned int length;
135  int ret = mvncGetResult(graph_->getHandle(),
136  reinterpret_cast<void**>(&result),
137  &length,
138  &user_param_);
140 
141  std::vector<uint16_t> result16_vector(reinterpret_cast<uint16_t*>(result),
142  reinterpret_cast<uint16_t*>(result) + length / 2);
143  std::vector<float> result32_vector;
144 
145  for (auto fp16 : result16_vector)
146  {
147  float fp32;
148 #ifdef SUPPORT_F16C
149  fp32 = _cvtsh_ss(fp16);
150 #else
151  Tensor::fp16tofp32(&fp32, fp16);
152 #endif
153  result32_vector.push_back(fp32);
154  }
155 
156  if (!cnn_type_.compare("tinyyolo_v1"))
157  {
158  result_->parseYoloResult(result32_vector, categories_, tensor_->getImageWidth(), tensor_->getImageHeight());
159  result_->setDetectionResult(graph_->getTimeTaken());
160  }
161  else if (!cnn_type_.compare("mobilenetssd"))
162  {
163  result_->parseSSDResult(result32_vector, categories_, tensor_->getImageWidth(), tensor_->getImageHeight());
164  result_->setDetectionResult(graph_->getTimeTaken());
165  }
166  else
167  {
168  ROS_ERROR("unsupported cnn model");
169  }
170  device_->monitorThermal();
171  }
172  catch (MvncMyriadError& e)
173  {
174  ROS_ERROR_STREAM(e.what());
175  std::string debug_info = graph_->getDebugInfo();
176  ROS_ERROR_STREAM("myriad debug info: " << debug_info);
177  }
178  catch (std::exception& e)
179  {
180  ROS_ERROR_STREAM(e.what());
181  }
182 }
183 
184 void NCS::loadTensor(const cv::Mat& image)
185 {
186  tensor_->clearTensor();
187  tensor_->loadImageData(image);
188 
189  assert(graph_->getHandle() != nullptr);
190  int ret = mvncLoadTensor(graph_->getHandle(),
191  tensor_->raw(),
192  tensor_->size(),
193  user_param_);
195 }
196 
198 {
199  return result_->getClassificationResult();
200 }
201 
203 {
204  return result_->getDetectionResult();
205 }
206 
208 {
209  device_.reset(new Device(device_index_,
210  static_cast<Device::LogLevel>(log_level_)));
211 }
212 
213 void NCS::loadGraph(const std::string& graph_file_path)
214 {
215  std::string graph = getFileContent(graph_file_path);
216  graph_.reset(new Graph(device_, graph, network_dimension_));
217 
218  ROS_INFO("graph is loaded");
219 }
220 
221 void NCS::loadCategories(const std::string& category_file_path)
222 {
223  try
224  {
225  std::string content = getFileContent(category_file_path);
226  splitIntoLines(content, categories_);
227  std::string first = categories_[0];
228  boost::trim_right(first);
229 
230  if (boost::iequals(first, "classes"))
231  {
232  categories_.erase(categories_.begin());
233  }
234  }
235  catch (int& e)
236  {
237  throw NCSLoadCategoriesError();
238  }
239 }
240 
241 void NCS::splitIntoLines(const std::string& content,
242  std::vector<std::string>& lines)
243 {
244  std::stringstream ss(content);
245  std::string line;
246 
247  while (std::getline(ss, line, '\n'))
248  {
249  lines.push_back(line);
250  }
251 }
252 
253 std::string NCS::getFileContent(const std::string& filename)
254 {
255  std::ifstream in(filename.c_str(), std::ios::in | std::ios::binary);
256 
257  if (!in)
258  {
259  throw(errno);
260  }
261 
262  std::string content;
263  in.seekg(0, std::ios::end);
264  content.reserve(in.tellg());
265  in.seekg(0, std::ios::beg);
266  content.assign(std::istreambuf_iterator<char>(in),
267  std::istreambuf_iterator<char>());
268  in.close();
269  return content;
270 }
271 } // namespace movidius_ncs_lib
const std::string cnn_type_
Definition: ncs.h:66
const int top_n_
Definition: ncs.h:71
std::shared_ptr< DetectionResult > DetectionResultPtr
Definition: result.h:64
const std::vector< float > mean_
Definition: ncs.h:69
Tensor::Ptr tensor_
Definition: ncs.h:61
static void fp16tofp32(float *__restrict out, uint16_t in)
Definition: tensor.cpp:89
void loadGraph(const std::string &graph_file_path)
Definition: ncs.cpp:213
static void tryToThrowMvncException(int code)
const char * what() const noexcept
Definition: exception.h:34
void loadCategories(const std::string &category_file_path)
Definition: ncs.cpp:221
Graph::Ptr graph_
Definition: ncs.h:60
static std::string getFileContent(const std::string &filename)
Definition: ncs.cpp:253
const float scale_
Definition: ncs.h:70
DetectionResultPtr getDetectionResult()
Definition: ncs.cpp:202
const int device_index_
Definition: ncs.h:64
static void splitIntoLines(const std::string &content, std::vector< std::string > &lines)
Definition: ncs.cpp:241
#define ROS_INFO(...)
Result::Ptr result_
Definition: ncs.h:62
std::vector< std::string > categories_
Definition: ncs.h:67
NCS(int device_index, 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.cpp:34
std::string category
Definition: result.h:28
std::shared_ptr< Items > ItemsPtr
Definition: result.h:47
std::shared_ptr< ClassificationResult > ClassificationResultPtr
Definition: result.h:63
Device::Ptr device_
Definition: ncs.h:59
const int network_dimension_
Definition: ncs.h:68
ClassificationResultPtr getClassificationResult()
Definition: ncs.cpp:197
void loadTensor(const cv::Mat &image)
Definition: ncs.cpp:184
#define ROS_ERROR_STREAM(args)
void * user_param_
Definition: ncs.h:72
const Device::LogLevel log_level_
Definition: ncs.h:65
#define ROS_ERROR(...)


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