ncs_server.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 <boost/filesystem/operations.hpp>
21 #include <cv_bridge/cv_bridge.h>
22 
23 #include <object_msgs/Object.h>
24 #include <object_msgs/Objects.h>
25 #include <object_msgs/ObjectInBox.h>
26 #include <object_msgs/ObjectsInBoxes.h>
28 
33 
34 namespace movidius_ncs_image
35 {
37  : ncs_manager_handle_(nullptr)
38  , nh_(nh)
39  , max_device_number_(255)
40  , start_device_index_(0)
41  , log_level_(Device::Errors)
42  , cnn_type_("")
43  , graph_file_path_("")
44  , category_file_path_("")
45  , network_dimension_(0)
46  , mean_(0)
47  , scale_(1.0)
48  , top_n_(1)
49 {
50  getParameters();
51  init();
52 }
53 
55 {
56  ROS_DEBUG("NCSServer get parameters");
57 
58  if (!nh_.getParam("max_device_number", max_device_number_))
59  {
60  ROS_WARN("param max_device_number not set, use default");
61  }
62 
63  if (max_device_number_ <= 0)
64  {
65  ROS_ERROR_STREAM("invalid param max_device_number = " << max_device_number_);
66  throw std::exception();
67  }
68 
69  ROS_INFO_STREAM("use max_device_number = " << max_device_number_);
70 
71  if (!nh_.getParam("start_device_index", start_device_index_))
72  {
73  ROS_WARN("param start_device_index not set, use default");
74  }
75 
76  if (start_device_index_ < 0)
77  {
78  ROS_ERROR_STREAM("invalid param start_device_index = " << start_device_index_);
79  throw std::exception();
80  }
81 
82  ROS_INFO_STREAM("use start_device_index = " << start_device_index_);
83 
84  if (!nh_.getParam("log_level", log_level_))
85  {
86  ROS_WARN("param log_level not set, use default");
87  }
88 
89  if (log_level_ < Device::Nothing || log_level_ > Device::Verbose)
90  {
91  ROS_WARN_STREAM("invalid param log_level = " << log_level_);
92  throw std::exception();
93  }
94 
95  ROS_INFO_STREAM("use log_level = " << log_level_);
96 
97  if (!nh_.getParam("cnn_type", cnn_type_))
98  {
99  ROS_WARN("param cnn_type not set, use default");
100  }
101 
102  if (cnn_type_.compare("alexnet") && cnn_type_.compare("googlenet") && cnn_type_.compare("inception_v1") &&
103  cnn_type_.compare("inception_v2") && cnn_type_.compare("inception_v3") && cnn_type_.compare("inception_v4") &&
104  cnn_type_.compare("mobilenet") && cnn_type_.compare("squeezenet") && cnn_type_.compare("tinyyolo_v1") &&
105  cnn_type_.compare("mobilenetssd"))
106  {
107  ROS_WARN_STREAM("invalid cnn_type_=" << cnn_type_);
108  throw std::exception();
109  }
110 
111  ROS_INFO_STREAM("use cnn_type_ = " << cnn_type_);
112 
113  if (!nh_.getParam("graph_file_path", graph_file_path_))
114  {
115  ROS_WARN("param graph_file_path not set, use default");
116  }
117 
118  if (!boost::filesystem::exists(graph_file_path_))
119  {
120  ROS_ERROR_STREAM("graph_file_path = " << graph_file_path_ << " not exists");
121  throw std::exception();
122  }
123 
124  ROS_INFO_STREAM("use graph_file_path = " << graph_file_path_);
125 
126  if (!nh_.getParam("category_file_path", category_file_path_))
127  {
128  ROS_WARN("param category_file_path not set, use default");
129  }
130 
131  if (!boost::filesystem::exists(category_file_path_))
132  {
133  ROS_ERROR_STREAM("category_file_path = " << category_file_path_ << " not exists");
134  throw std::exception();
135  }
136 
137  ROS_INFO_STREAM("use category_file_path = " << category_file_path_);
138 
139  if (!nh_.getParam("network_dimension", network_dimension_))
140  {
141  ROS_WARN("param network_dimension not set, use default");
142  }
143 
144  if (network_dimension_ < 0)
145  {
146  ROS_WARN_STREAM("invalid network_dimension = " << network_dimension_);
147  throw std::exception();
148  }
149 
150  ROS_INFO_STREAM("use network_dimension = " << network_dimension_);
151 
152  for (int i = 0; i < 3; i++)
153  {
154  std::ostringstream oss;
155  oss << "channel" << (i + 1) << "_mean";
156  std::string mean_param_name = oss.str();
157  float mean_val;
158  if (!nh_.getParam(mean_param_name, mean_val))
159  {
160  ROS_WARN_STREAM("param " << mean_param_name << "not set, use default");
161  }
162  ROS_INFO_STREAM("use " << mean_param_name << " = " << mean_val);
163  mean_.push_back(mean_val);
164  }
165 
166  if (!nh_.getParam("top_n", top_n_))
167  {
168  ROS_WARN("param top_n not set, use default");
169  }
170 
171  if (top_n_ < 1)
172  {
173  ROS_WARN_STREAM("invalid top_n = " << top_n_);
174  throw std::exception();
175  }
176 
177  ROS_INFO_STREAM("use top_n = " << top_n_);
178 
179  if (!nh_.getParam("scale", scale_))
180  {
181  ROS_WARN("param scale not set, use default");
182  }
183 
184  if (scale_ < 0)
185  {
186  ROS_WARN_STREAM("invalid param scale = " << scale_);
187  throw std::exception();
188  }
189 
190  ROS_INFO_STREAM("use scale = " << scale_);
191 }
192 
194 {
195  ROS_DEBUG("NCSServer init");
196 
197  ncs_manager_handle_ = std::make_shared<NCSManager>(
200 
201  if (!cnn_type_.compare("alexnet") || !cnn_type_.compare("googlenet") || !cnn_type_.compare("inception_v1") ||
202  !cnn_type_.compare("inception_v2") || !cnn_type_.compare("inception_v3") || !cnn_type_.compare("inception_v4") ||
203  !cnn_type_.compare("mobilenet") || !cnn_type_.compare("squeezenet"))
204  {
205  service_ = nh_.advertiseService("classify_object", &NCSServer::cbClassifyObject, this);
206  }
207  else
208  {
209  service_ = nh_.advertiseService("detect_object", &NCSServer::cbDetectObject, this);
210  }
211 }
212 
213 bool NCSServer::cbClassifyObject(object_msgs::ClassifyObject::Request& request,
214  object_msgs::ClassifyObject::Response& response)
215 {
216  std::vector<ClassificationResultPtr> results = ncs_manager_handle_->classifyImage(request.image_paths);
217 
218  for (unsigned int i = 0; i < results.size(); i++)
219  {
220  object_msgs::Objects objs;
221  for (auto item : results[i]->items)
222  {
223  object_msgs::Object obj;
224  obj.object_name = item.category;
225  obj.probability = item.probability;
226  objs.objects_vector.push_back(obj);
227  }
228 
229  objs.inference_time_ms = results[i]->time_taken;
230  response.objects.push_back(objs);
231  }
232 
233  return true;
234 }
235 
236 bool NCSServer::cbDetectObject(object_msgs::DetectObject::Request& request,
237  object_msgs::DetectObject::Response& response)
238 {
239  std::vector<DetectionResultPtr> results = ncs_manager_handle_->detectImage(request.image_paths);
240 
241  for (unsigned int i = 0; i < results.size(); i++)
242  {
243  object_msgs::ObjectsInBoxes objs;
244  for (auto item : results[i]->items_in_boxes)
245  {
246  object_msgs::ObjectInBox obj;
247  obj.object.object_name = item.item.category;
248  obj.object.probability = item.item.probability;
249  obj.roi.x_offset = item.bbox.x;
250  obj.roi.y_offset = item.bbox.y;
251  obj.roi.width = item.bbox.width;
252  obj.roi.height = item.bbox.height;
253  objs.objects_vector.push_back(obj);
254  }
255 
256  objs.inference_time_ms = results[i]->time_taken;
257  response.objects.push_back(objs);
258  }
259 
260  return true;
261 }
262 
263 } // namespace movidius_ncs_image
264 
265 int main(int argc, char** argv)
266 {
267  ros::init(argc, argv, "movidius_ncs_node");
268  ros::NodeHandle nh("~");
269 
270  try
271  {
273  ros::spin();
274  }
275  catch (...)
276  {
277  ROS_ERROR("exception caught in movidius_ncs_node");
278  }
279 }
std::shared_ptr< DetectionResult > DetectionResultPtr
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ros::ServiceServer service_
Definition: ncs_server.h:44
std::shared_ptr< movidius_ncs_lib::NCSManager > ncs_manager_handle_
Definition: ncs_server.h:46
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
#define ROS_WARN(...)
bool cbDetectObject(object_msgs::DetectObject::Request &request, object_msgs::DetectObject::Response &response)
Definition: ncs_server.cpp:236
ROSCPP_DECL void spin(Spinner &spinner)
NCSServer(ros::NodeHandle &nh)
Definition: ncs_server.cpp:36
#define ROS_WARN_STREAM(args)
std::vector< float > mean_
Definition: ncs_server.h:56
std::shared_ptr< ClassificationResult > ClassificationResultPtr
#define ROS_INFO_STREAM(args)
bool getParam(const std::string &key, std::string &s) const
int main(int argc, char **argv)
Definition: ncs_server.cpp:265
#define ROS_ERROR_STREAM(args)
#define ROS_ERROR(...)
bool cbClassifyObject(object_msgs::ClassifyObject::Request &request, object_msgs::ClassifyObject::Response &response)
Definition: ncs_server.cpp:213
#define ROS_DEBUG(...)


movidius_ncs_image
Author(s): Xiaojun Huang
autogenerated on Mon Jun 10 2019 14:11:26