20 #include <image_transport/image_transport.h> 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)
33 , graph_file_path_(graph_file_path)
34 , category_file_path_(category_file_path)
35 , network_dimension_(network_dimension)
39 , user_param_(nullptr)
51 char device_name[MVNC_MAX_NAME_SIZE];
52 while (mvncGetDeviceName(
device_count_, device_name,
sizeof(device_name)) != MVNC_DEVICE_NOT_FOUND)
106 p_c_(result, first_image_header);
114 p_d_(result, first_image_header);
138 int image_size =
static_cast<int>(images.size());
139 std::vector<ClassificationResultPtr> results(image_size);
144 for (
int i = 0; i < parallel_group; i++)
146 #pragma omp parallel for 149 cv::Mat imageData = cv::imread(images[i * (
device_count_ - start_device_index_) + device_index]);
154 std::make_shared<ClassificationResult>(*result);
158 for (
int j = 0; j < parallel_left; j++)
165 std::make_shared<ClassificationResult>(*result);
173 int image_size =
static_cast<int>(images.size());
174 std::vector<DetectionResultPtr> results(image_size);
179 for (
int i = 0; i < parallel_group; i++)
181 #pragma omp parallel for 184 cv::Mat imageData = cv::imread(images[i * (
device_count_ - start_device_index_) + device_index]);
192 for (
int i = 0; i < parallel_left; i++)
205 const sensor_msgs::ImageConstPtr& image_msg)
207 p_c_ = cbGetClassificationResult;
210 imageFrame.
header = image_msg->header;
211 imageFrame.
image = image;
223 const sensor_msgs::ImageConstPtr& image_msg)
225 p_d_ = cbGetDetectionResult;
228 imageFrame.
header = image_msg->header;
229 imageFrame.
image = image;
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)
const int start_device_index_
std::vector< DetectionResultPtr > detectImage(const std::vector< std::string > &images)
std::shared_ptr< DetectionResult > DetectionResultPtr
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_
void deviceThread(int device_index)
void classifyStream(const cv::Mat &image, FUNP_C cbGetClassificationResult, const sensor_msgs::ImageConstPtr &image_msg)
std::vector< std::thread > threads_
const Device::LogLevel log_level_
boost::function< void(ClassificationResultPtr result, std_msgs::Header header)> FUNP_C
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)
const int network_dimension_
std::vector< ImageFrame > image_list_
const std::string cnn_type_
void join(std::thread &t)
std::shared_ptr< ClassificationResult > ClassificationResultPtr
const std::string category_file_path_
const std::string graph_file_path_
#define IMAGE_BUFFER_SIZE