17 #ifndef MOVIDIUS_NCS_LIB_NCS_MANAGER_H 18 #define MOVIDIUS_NCS_LIB_NCS_MANAGER_H 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> 33 #define IMAGE_BUFFER_SIZE 10 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;
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);
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);
64 void initDeviceManager();
65 void deviceThread(
int device_index);
90 #endif // MOVIDIUS_NCS_LIB_NCS_MANAGER_H const int start_device_index_
const std::vector< float > mean_
const int max_device_number_
boost::function< void(DetectionResultPtr result, std_msgs::Header header)> FUNP_D
std::vector< std::shared_ptr< movidius_ncs_lib::NCS > > ncs_handle_list_
std::vector< std::thread > threads_
const Device::LogLevel log_level_
boost::function< void(ClassificationResultPtr result, std_msgs::Header header)> FUNP_C
const int network_dimension_
std::vector< ImageFrame > image_list_
const std::string cnn_type_
const std::string category_file_path_
const std::string graph_file_path_