ncs_nodelet.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_STREAM_NCS_NODELET_H
18 #define MOVIDIUS_NCS_STREAM_NCS_NODELET_H
19 
20 #include <string>
21 #include <vector>
22 
23 #include <boost/bind.hpp>
24 #include <boost/function.hpp>
25 #include <nodelet/nodelet.h>
26 #include <ros/ros.h>
27 #include <sensor_msgs/Image.h>
28 #include "movidius_ncs_lib/ncs.h"
30 
32 {
33 typedef boost::function<void(movidius_ncs_lib::ClassificationResultPtr result, std_msgs::Header header)> FUNP_C;
34 typedef boost::function<void(movidius_ncs_lib::DetectionResultPtr result, std_msgs::Header header)> FUNP_D;
35 
36 class NCSImpl
37 {
38 public:
40  ~NCSImpl();
41 
42  void cbGetClassificationResult(movidius_ncs_lib::ClassificationResultPtr result, std_msgs::Header header);
43  void cbGetDetectionResult(movidius_ncs_lib::DetectionResultPtr result, std_msgs::Header header);
44 
45 private:
46  void cbClassify(const sensor_msgs::ImageConstPtr& image);
47  void cbDetect(const sensor_msgs::ImageConstPtr& image);
48  void getParameters();
49  void init();
50 
51  std::shared_ptr<movidius_ncs_lib::NCSManager> ncs_manager_handle_;
52 
57 
61  std::string cnn_type_;
62  std::string graph_file_path_;
63  std::string category_file_path_;
65  std::vector<float> mean_;
66  float scale_;
67  int top_n_;
68 };
69 
71 {
72 public:
73  virtual ~NCSNodelet();
74 
75 private:
76  virtual void onInit();
77 
78  std::shared_ptr<NCSImpl> impl_;
79 };
80 } // namespace movidius_ncs_stream
81 
82 #endif // MOVIDIUS_NCS_STREAM_NCS_NODELET_H
std::vector< float > mean_
Definition: ncs_nodelet.h:65
std::shared_ptr< DetectionResult > DetectionResultPtr
boost::function< void(movidius_ncs_lib::DetectionResultPtr result, std_msgs::Header header)> FUNP_D
Definition: ncs_nodelet.h:34
NCSImpl(ros::NodeHandle &nh, ros::NodeHandle &pnh)
Definition: ncs_nodelet.cpp:39
void cbGetClassificationResult(movidius_ncs_lib::ClassificationResultPtr result, std_msgs::Header header)
void cbGetDetectionResult(movidius_ncs_lib::DetectionResultPtr result, std_msgs::Header header)
boost::function< void(movidius_ncs_lib::ClassificationResultPtr result, std_msgs::Header header)> FUNP_C
Definition: ncs_nodelet.h:33
std::shared_ptr< ClassificationResult > ClassificationResultPtr
std::shared_ptr< NCSImpl > impl_
Definition: ncs_nodelet.h:78
void cbClassify(const sensor_msgs::ImageConstPtr &image)
void cbDetect(const sensor_msgs::ImageConstPtr &image)
image_transport::Subscriber sub_
Definition: ncs_nodelet.h:54
std::shared_ptr< movidius_ncs_lib::NCSManager > ncs_manager_handle_
Definition: ncs_nodelet.h:51


movidius_ncs_stream
Author(s): Xiaojun Huang
autogenerated on Mon Jun 10 2019 14:11:28