ncs_manager.h
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 #ifndef MOVIDIUS_NCS_LIB_NCS_MANAGER_H
18 #define MOVIDIUS_NCS_LIB_NCS_MANAGER_H
19 
20 #include <mutex>
21 #include <string>
22 #include <thread>
23 #include <vector>
24 
25 #include "boost/bind.hpp"
26 #include "boost/function.hpp"
27 #include <cv_bridge/cv_bridge.h>
28 #include <opencv2/opencv.hpp>
29 #include <sensor_msgs/Image.h>
31 #include "movidius_ncs_lib/ncs.h"
32 
33 #define IMAGE_BUFFER_SIZE 10
34 
35 namespace movidius_ncs_lib
36 {
37 typedef boost::function<void(ClassificationResultPtr result, std_msgs::Header header)> FUNP_C;
38 typedef boost::function<void(DetectionResultPtr result, std_msgs::Header header)> FUNP_D;
39 
40 struct ImageFrame
41 {
42  cv::Mat image;
43  std_msgs::Header header;
44 };
45 
47 {
48 public:
49  NCSManager(const int& max_device_number, const int& device_index, const Device::LogLevel& log_level,
50  const std::string& cnn_type, const std::string& graph_file_path, const std::string& category_file_path,
51  const int& network_dimension, const std::vector<float>& mean, const float& scale, const int& top_n);
52  ~NCSManager();
53 
54  void startThreads();
55 
56  void classifyStream(const cv::Mat& image, FUNP_C cbGetClassificationResult,
57  const sensor_msgs::ImageConstPtr& image_msg);
58  void detectStream(const cv::Mat& image, FUNP_D cbGetDetectionResult,
59  const sensor_msgs::ImageConstPtr& image_msg);
60  std::vector<ClassificationResultPtr> classifyImage(const std::vector<std::string>& images);
61  std::vector<DetectionResultPtr> detectImage(const std::vector<std::string>& images);
62 
63 private:
64  void initDeviceManager();
65  void deviceThread(int device_index);
66 
67  const int max_device_number_;
70  const std::string cnn_type_;
71  const std::string graph_file_path_;
72  const std::string category_file_path_;
73  const int network_dimension_;
74  const std::vector<float> mean_;
75  const float scale_;
76  const int top_n_;
77  void* user_param_;
78 
79  std::vector<std::shared_ptr<movidius_ncs_lib::NCS>> ncs_handle_list_;
81 
82  FUNP_C p_c_;
83  FUNP_D p_d_;
84 
85  std::vector<ImageFrame> image_list_;
86  std::mutex mtx_;
87  std::vector<std::thread> threads_;
88 };
89 } // namespace movidius_ncs_lib
90 #endif // MOVIDIUS_NCS_LIB_NCS_MANAGER_H
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
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
std::vector< ImageFrame > image_list_
Definition: ncs_manager.h:85
const std::string cnn_type_
Definition: ncs_manager.h:70
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


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