# ROS2 Foxy and OpenVINO 2021.3 on Ubuntu 20.04 ## Run demo source ~/ros2_foxy/install/local_setup.bash source /opt/intel/openvino_2021/bin/setupvars.sh cd my_ros2_ws/src source ./install/local_setup.bash ros2 launch dynamic_vino_sample pipeline_image.launch.py ![](https://i.imgur.com/3Ven4TC.png) ## Follow step in link below and no need to install cmake 3.14 on ubuntu 20.04 https://github.com/intel/ros2_openvino_toolkit/blob/master/doc/getting_started_with_Foxy.md Install realsense SDK is required https://github.com/IntelRealSense/librealsense/blob/master/doc/distribution_linux.md ``` sudo apt-key adv --keyserver keys.gnupg.net --recv-key F6E65AC044F831AC80A06380C8B3A55A6F3EFCDE || sudo apt-key adv --keyserver hkp://keyserver.ubuntu.com:80 --recv-key F6E65AC044F831AC80A06380C8B3A55A6F3EFCDE sudo add-apt-repository "deb https://librealsense.intel.com/Debian/apt-repo focal main" -u sudo apt-get install librealsense2-dkms sudo apt-get install librealsense2-utils sudo apt-get install librealsense2-dev sudo apt-get install librealsense2-dbg ``` Required to build packages in my_ros2_ws, sudo apt install libboost-python-dev ### requires #include <set> in /home/openvino/my_ros2_ws/src/image_common/image_transport/src/publisher.cpp ``` /my_ros2_ws/src/image_common/image_transport$ git diff diff --git a/image_transport/src/publisher.cpp b/image_transport/src/publisher.cpp index 26f16a6..51ea0e0 100644 --- a/image_transport/src/publisher.cpp +++ b/image_transport/src/publisher.cpp @@ -41,6 +41,7 @@ #include <rclcpp/node.hpp> #include <pluginlib/class_loader.hpp> +#include <set> namespace image_transport { ``` ``` Starting >>> pipeline_srv_msgs --- stderr: image_transport /home/openvino/my_ros2_ws/src/image_common/image_transport/src/publisher.cpp: In constructor ‘image_transport::Publisher::Publisher(rclcpp::Node*, const string&, image_transport::PubLoaderPtr, rmw_qos_profile_t)’: /home/openvino/my_ros2_ws/src/image_common/image_transport/src/publisher.cpp:111:8: error: ‘set’ is not a member of ‘std’ 111 | std::set<std::string> blacklist; | ^~~ /home/openvino/my_ros2_ws/src/image_common/image_transport/src/publisher.cpp:44:1: note: ‘std::set’ is defined in header ‘<set>’; did you forget to ‘#include <set>’? 43 | #include <pluginlib/class_loader.hpp> +++ |+#include <set> 44 | /home/openvino/my_ros2_ws/src/image_common/image_transport/src/publisher.cpp:111:23: error: expected primary-expression before ‘>’ token 111 | std::set<std::string> blacklist; | ^ /home/openvino/my_ros2_ws/src/image_common/image_transport/src/publisher.cpp:111:25: error: ‘blacklist’ was not declared in this scope 111 | std::set<std::string> blacklist; | ^~~~~~~~~ make[2]: *** [CMakeFiles/image_transport.dir/build.make:95: CMakeFiles/image_transport.dir/src/publisher.cpp.o] Error 1 make[2]: *** Waiting for unfinished jobs.... make[1]: *** [CMakeFiles/Makefile2:219: CMakeFiles/image_transport.dir/all] Error 2 make: *** [Makefile:160: all] Error 2 --- Failed <<< image_transport [18.7s, exited with code 2] Aborted <<< people_msgs [9.28s] Aborted <<< pipeline_srv_msgs [9.26s] Aborted <<< realsense_ros [29.4s] Summary: 9 packages finished [34.5s] 1 package failed: image_transport 3 packages aborted: people_msgs pipeline_srv_msgs realsense_ros 2 packages had stderr output: image_transport realsense_ros 6 packages not processed ``` ## https://software.intel.com/content/www/us/en/develop/articles/openvino-relnotes.html /home/openvino/my_ros2_ws/src/ros2_openvino_toolkit/dynamic_vino_lib/include/dynamic_vino_lib/models/attributes/base_attribute.hpp:89:28: error: ‘CNNNetReader’ in namespace ‘InferenceEngine’ does not name a type CNNNetReader class. Use Core::ReadNetwork instead. ## Below are patch for ros2_openvino_toolkit ``` ~/my_ros2_ws/src/ros2_openvino_toolkit$ cat ~/ros2_openvino_toolkit.patch diff --git a/dynamic_vino_lib/include/dynamic_vino_lib/models/age_gender_detection_model.hpp b/dynamic_vino_lib/include/dynamic_vino_lib/models/age_gender_detection_model.hpp index 8d614a3..1a5d501 100644 --- a/dynamic_vino_lib/include/dynamic_vino_lib/models/age_gender_detection_model.hpp +++ b/dynamic_vino_lib/include/dynamic_vino_lib/models/age_gender_detection_model.hpp @@ -61,7 +61,7 @@ public: const std::string getModelCategory() const override; protected: - bool updateLayerProperty(InferenceEngine::CNNNetReader::Ptr) override; + bool updateLayerProperty(InferenceEngine::CNNNetwork&) override; }; } // namespace Models diff --git a/dynamic_vino_lib/include/dynamic_vino_lib/models/attributes/base_attribute.hpp b/dynamic_vino_lib/include/dynamic_vino_lib/models/attributes/base_attribute.hpp index 4e529e2..061a1c2 100644 --- a/dynamic_vino_lib/include/dynamic_vino_lib/models/attributes/base_attribute.hpp +++ b/dynamic_vino_lib/include/dynamic_vino_lib/models/attributes/base_attribute.hpp @@ -86,7 +86,7 @@ public: } virtual bool updateLayerProperty( - const InferenceEngine::CNNNetReader::Ptr &) + const InferenceEngine::CNNNetwork&) { return false; } inline std::string getModelName() const @@ -187,7 +187,7 @@ public: explicit SSDModelAttr(const std::string model_name = "SSDNet-like"); bool updateLayerProperty( - const InferenceEngine::CNNNetReader::Ptr &); + const InferenceEngine::CNNNetwork&); }; diff --git a/dynamic_vino_lib/include/dynamic_vino_lib/models/base_model.hpp b/dynamic_vino_lib/include/dynamic_vino_lib/models/base_model.hpp index 8748003..f337967 100644 --- a/dynamic_vino_lib/include/dynamic_vino_lib/models/base_model.hpp +++ b/dynamic_vino_lib/include/dynamic_vino_lib/models/base_model.hpp @@ -95,7 +95,7 @@ namespace Models virtual const std::string getModelCategory() const = 0; inline ModelAttr getAttribute() { return attr_; } - inline InferenceEngine::CNNNetReader::Ptr getNetReader() const + inline InferenceEngine::CNNNetwork getNetReader() const { return net_reader_; } @@ -106,9 +106,11 @@ namespace Models * @brief Set the layer property (layer layout, layer precision, etc.). * @param[in] network_reader The reader of the network to be set. */ - virtual bool updateLayerProperty(InferenceEngine::CNNNetReader::Ptr network_reader) = 0; + virtual bool updateLayerProperty(InferenceEngine::CNNNetwork& network_reader) = 0; - InferenceEngine::CNNNetReader::Ptr net_reader_; + ///InferenceEngine::CNNNetReader::Ptr net_reader_; + InferenceEngine::Core engine; + InferenceEngine::CNNNetwork net_reader_; // = engine.ReadNetwork(model->getModelFileName()); void setFrameSize(const int &w, const int &h) { frame_size_.width = w; diff --git a/dynamic_vino_lib/include/dynamic_vino_lib/models/emotion_detection_model.hpp b/dynamic_vino_lib/include/dynamic_vino_lib/models/emotion_detection_model.hpp index 1f2749f..edf9682 100644 --- a/dynamic_vino_lib/include/dynamic_vino_lib/models/emotion_detection_model.hpp +++ b/dynamic_vino_lib/include/dynamic_vino_lib/models/emotion_detection_model.hpp @@ -39,7 +39,7 @@ public: * @return Name of the model. */ const std::string getModelCategory() const override; - bool updateLayerProperty(InferenceEngine::CNNNetReader::Ptr) override; + bool updateLayerProperty(InferenceEngine::CNNNetwork&) override; private: bool verifyOutputLayer(const InferenceEngine::DataPtr & ptr); diff --git a/dynamic_vino_lib/include/dynamic_vino_lib/models/head_pose_detection_model.hpp b/dynamic_vino_lib/include/dynamic_vino_lib/models/head_pose_detection_model.hpp index 4d07367..1b0bc1b 100644 --- a/dynamic_vino_lib/include/dynamic_vino_lib/models/head_pose_detection_model.hpp +++ b/dynamic_vino_lib/include/dynamic_vino_lib/models/head_pose_detection_model.hpp @@ -63,7 +63,7 @@ public: * @return Name of the model. */ const std::string getModelCategory() const override; - bool updateLayerProperty(InferenceEngine::CNNNetReader::Ptr) override; + bool updateLayerProperty(InferenceEngine::CNNNetwork&) override; private: diff --git a/dynamic_vino_lib/include/dynamic_vino_lib/models/license_plate_detection_model.hpp b/dynamic_vino_lib/include/dynamic_vino_lib/models/license_plate_detection_model.hpp index e0b5f9c..0074f76 100644 --- a/dynamic_vino_lib/include/dynamic_vino_lib/models/license_plate_detection_model.hpp +++ b/dynamic_vino_lib/include/dynamic_vino_lib/models/license_plate_detection_model.hpp @@ -43,7 +43,7 @@ public: protected: //void checkLayerProperty(const InferenceEngine::CNNNetReader::Ptr &) override; //void setLayerProperty(InferenceEngine::CNNNetReader::Ptr) override; - bool updateLayerProperty(InferenceEngine::CNNNetReader::Ptr) override; + bool updateLayerProperty(InferenceEngine::CNNNetwork&) override; // up to 88 items per license plate, ended with "-1" const int max_sequence_size_ = 88; std::string input_; diff --git a/dynamic_vino_lib/include/dynamic_vino_lib/models/object_detection_ssd_model.hpp b/dynamic_vino_lib/include/dynamic_vino_lib/models/object_detection_ssd_model.hpp index 99db656..cca96f7 100644 --- a/dynamic_vino_lib/include/dynamic_vino_lib/models/object_detection_ssd_model.hpp +++ b/dynamic_vino_lib/include/dynamic_vino_lib/models/object_detection_ssd_model.hpp @@ -55,7 +55,7 @@ public: */ const std::string getModelCategory() const override; - bool updateLayerProperty(InferenceEngine::CNNNetReader::Ptr) override; + bool updateLayerProperty(InferenceEngine::CNNNetwork&) override; }; } // namespace Models diff --git a/dynamic_vino_lib/include/dynamic_vino_lib/models/object_detection_yolov2_model.hpp b/dynamic_vino_lib/include/dynamic_vino_lib/models/object_detection_yolov2_model.hpp index a779dfe..25f2b98 100644 --- a/dynamic_vino_lib/include/dynamic_vino_lib/models/object_detection_yolov2_model.hpp +++ b/dynamic_vino_lib/include/dynamic_vino_lib/models/object_detection_yolov2_model.hpp @@ -54,7 +54,7 @@ public: * @return Name of the model. */ const std::string getModelCategory() const override; - bool updateLayerProperty(InferenceEngine::CNNNetReader::Ptr) override; + bool updateLayerProperty(InferenceEngine::CNNNetwork&) override; protected: int getEntryIndex(int side, int lcoords, int lclasses, int location, int entry); diff --git a/dynamic_vino_lib/include/dynamic_vino_lib/models/object_segmentation_model.hpp b/dynamic_vino_lib/include/dynamic_vino_lib/models/object_segmentation_model.hpp index 0ab42f1..c17bba8 100644 --- a/dynamic_vino_lib/include/dynamic_vino_lib/models/object_segmentation_model.hpp +++ b/dynamic_vino_lib/include/dynamic_vino_lib/models/object_segmentation_model.hpp @@ -50,7 +50,7 @@ public: * @return Name of the model. */ const std::string getModelCategory() const override; - bool updateLayerProperty(InferenceEngine::CNNNetReader::Ptr) override; + bool updateLayerProperty(InferenceEngine::CNNNetwork&) override; private: int max_proposal_count_; diff --git a/dynamic_vino_lib/include/dynamic_vino_lib/models/person_attribs_detection_model.hpp b/dynamic_vino_lib/include/dynamic_vino_lib/models/person_attribs_detection_model.hpp index a1581b7..0389f2c 100644 --- a/dynamic_vino_lib/include/dynamic_vino_lib/models/person_attribs_detection_model.hpp +++ b/dynamic_vino_lib/include/dynamic_vino_lib/models/person_attribs_detection_model.hpp @@ -41,7 +41,7 @@ public: protected: //void checkLayerProperty(const InferenceEngine::CNNNetReader::Ptr &) override; //void setLayerProperty(InferenceEngine::CNNNetReader::Ptr) override; - bool updateLayerProperty(InferenceEngine::CNNNetReader::Ptr) override; + bool updateLayerProperty(InferenceEngine::CNNNetwork&) override; std::string input_; std::string output_; }; diff --git a/dynamic_vino_lib/include/dynamic_vino_lib/models/person_reidentification_model.hpp b/dynamic_vino_lib/include/dynamic_vino_lib/models/person_reidentification_model.hpp index 88202c7..57be91b 100644 --- a/dynamic_vino_lib/include/dynamic_vino_lib/models/person_reidentification_model.hpp +++ b/dynamic_vino_lib/include/dynamic_vino_lib/models/person_reidentification_model.hpp @@ -39,7 +39,7 @@ public: const std::string getModelCategory() const override; protected: - bool updateLayerProperty(InferenceEngine::CNNNetReader::Ptr) override; + bool updateLayerProperty(InferenceEngine::CNNNetwork&) override; //void checkLayerProperty(const InferenceEngine::CNNNetReader::Ptr &) override; //void setLayerProperty(InferenceEngine::CNNNetReader::Ptr) override; std::string input_; diff --git a/dynamic_vino_lib/include/dynamic_vino_lib/models/vehicle_attribs_detection_model.hpp b/dynamic_vino_lib/include/dynamic_vino_lib/models/vehicle_attribs_detection_model.hpp index 0e6601a..38b452f 100644 --- a/dynamic_vino_lib/include/dynamic_vino_lib/models/vehicle_attribs_detection_model.hpp +++ b/dynamic_vino_lib/include/dynamic_vino_lib/models/vehicle_attribs_detection_model.hpp @@ -42,7 +42,7 @@ public: protected: //void checkLayerProperty(const InferenceEngine::CNNNetReader::Ptr &) override; //void setLayerProperty(InferenceEngine::CNNNetReader::Ptr) override; - bool updateLayerProperty(InferenceEngine::CNNNetReader::Ptr) override; + bool updateLayerProperty(InferenceEngine::CNNNetwork&) override; std::string input_; std::string color_output_; std::string type_output_; diff --git a/dynamic_vino_lib/include/dynamic_vino_lib/utils/version_info.hpp b/dynamic_vino_lib/include/dynamic_vino_lib/utils/version_info.hpp index 431fa86..abeac0c 100644 --- a/dynamic_vino_lib/include/dynamic_vino_lib/utils/version_info.hpp +++ b/dynamic_vino_lib/include/dynamic_vino_lib/utils/version_info.hpp @@ -20,10 +20,6 @@ #ifndef DYNAMIC_VINO_LIB__UTILS__VERSION_INFO_HPP_ #define DYNAMIC_VINO_LIB__UTILS__VERSION_INFO_HPP_ -#include <ie_plugin_dispatcher.hpp> -#include <ie_plugin_ptr.hpp> -#include <cpp/ie_cnn_net_reader.h> -#include <cpp/ie_infer_request.hpp> #if(defined(USE_OLD_E_PLUGIN_API)) #include <ie_device.hpp> #endif diff --git a/dynamic_vino_lib/src/engines/engine_manager.cpp b/dynamic_vino_lib/src/engines/engine_manager.cpp index 501d74c..ed0e3ef 100644 --- a/dynamic_vino_lib/src/engines/engine_manager.cpp +++ b/dynamic_vino_lib/src/engines/engine_manager.cpp @@ -41,7 +41,7 @@ std::shared_ptr<Engines::Engine> Engines::EngineManager::createEngine_V2019R2_pl const std::string & device, const std::shared_ptr<Models::BaseModel> & model) { InferenceEngine::Core core; - auto executable_network = core.LoadNetwork(model->getNetReader()->getNetwork(), device); + auto executable_network = core.LoadNetwork(model->getNetReader(), device); auto request = executable_network.CreateInferRequestPtr(); return std::make_shared<Engines::Engine>(request); diff --git a/dynamic_vino_lib/src/models/age_gender_detection_model.cpp b/dynamic_vino_lib/src/models/age_gender_detection_model.cpp index ae8d86f..480f6a0 100644 --- a/dynamic_vino_lib/src/models/age_gender_detection_model.cpp +++ b/dynamic_vino_lib/src/models/age_gender_detection_model.cpp @@ -30,11 +30,11 @@ Models::AgeGenderDetectionModel::AgeGenderDetectionModel( { } bool Models::AgeGenderDetectionModel::updateLayerProperty( - InferenceEngine::CNNNetReader::Ptr net_reader) + InferenceEngine::CNNNetwork& net_reader) { slog::info << "Checking INPUTs for model " << getModelName() << slog::endl; // set input property - InferenceEngine::InputsDataMap input_info_map(net_reader->getNetwork().getInputsInfo()); + InferenceEngine::InputsDataMap input_info_map(net_reader.getInputsInfo()); if (input_info_map.size() != 1) { slog::warn << "This model seems not Age-Gender-like, which should have only one input," <<" but we got " << std::to_string(input_info_map.size()) << "inputs" @@ -46,7 +46,7 @@ bool Models::AgeGenderDetectionModel::updateLayerProperty( input_info->setLayout(InferenceEngine::Layout::NCHW); addInputInfo("input", input_info_map.begin()->first); // set output property - InferenceEngine::OutputsDataMap output_info_map(net_reader->getNetwork().getOutputsInfo()); + InferenceEngine::OutputsDataMap output_info_map(net_reader.getOutputsInfo()); if (output_info_map.size() != 2) { // throw std::logic_error("Age/Gender Recognition network should have two output layers"); slog::warn << "This model seems not Age-gender like, which should have and only have 2" @@ -58,6 +58,7 @@ bool Models::AgeGenderDetectionModel::updateLayerProperty( InferenceEngine::DataPtr age_output_ptr = (it++)->second; InferenceEngine::DataPtr gender_output_ptr = (it++)->second; +#if(0) /// //Check More Configuration: if (gender_output_ptr->getCreatorLayer().lock()->type == "Convolution") { std::swap(age_output_ptr, gender_output_ptr); @@ -79,6 +80,7 @@ bool Models::AgeGenderDetectionModel::updateLayerProperty( } slog::info << "Age layer: " << age_output_ptr->getCreatorLayer().lock()->name << slog::endl; slog::info << "Gender layer: " << gender_output_ptr->getCreatorLayer().lock()->name << slog::endl; +#endif age_output_ptr->setPrecision(InferenceEngine::Precision::FP32); age_output_ptr->setLayout(InferenceEngine::Layout::NCHW); diff --git a/dynamic_vino_lib/src/models/attributes/ssd_model_attr.cpp b/dynamic_vino_lib/src/models/attributes/ssd_model_attr.cpp index f0968fc..c2924c6 100644 --- a/dynamic_vino_lib/src/models/attributes/ssd_model_attr.cpp +++ b/dynamic_vino_lib/src/models/attributes/ssd_model_attr.cpp @@ -30,11 +30,11 @@ Models::SSDModelAttr::SSDModelAttr( } bool Models::SSDModelAttr::updateLayerProperty( - const InferenceEngine::CNNNetReader::Ptr & net_reader) + const InferenceEngine::CNNNetwork & net_reader) { slog::info << "Checking INPUTs for model " << getModelName() << slog::endl; - InferenceEngine::InputsDataMap input_info_map(net_reader->getNetwork().getInputsInfo()); + InferenceEngine::InputsDataMap input_info_map(net_reader.getInputsInfo()); if (input_info_map.size() != 1) { slog::warn << "This model seems not SSDNet-like, SSDnet has only one input, but we got " << std::to_string(input_info_map.size()) << "inputs" << slog::endl; @@ -50,7 +50,7 @@ bool Models::SSDModelAttr::updateLayerProperty( setInputWidth(input_dims[3]); slog::info << "Checking OUTPUTs for model " << getModelName() << slog::endl; - InferenceEngine::OutputsDataMap output_info_map(net_reader->getNetwork().getOutputsInfo()); + InferenceEngine::OutputsDataMap output_info_map(net_reader.getOutputsInfo()); if (output_info_map.size() != 1) { slog::warn << "This model seems not SSDNet-like! We got " << std::to_string(output_info_map.size()) << "outputs, but SSDnet has only one." @@ -64,6 +64,7 @@ bool Models::SSDModelAttr::updateLayerProperty( output_data_ptr->setPrecision(InferenceEngine::Precision::FP32); ///TODO: double check this part: BEGIN +#if(0) /// const InferenceEngine::CNNLayerPtr output_layer = net_reader->getNetwork().getLayerByName(output_info_map.begin()->first.c_str()); // output layer should have attribute called num_classes @@ -76,6 +77,7 @@ bool Models::SSDModelAttr::updateLayerProperty( // class number should be equal to size of label vector // if network has default "background" class, fake is used const int num_classes = output_layer->GetParamAsInt("num_classes"); +#endif #if 0 slog::info << "Checking Object Detection output ... num_classes=" << num_classes << slog::endl; if (getLabels().size() != num_classes) { diff --git a/dynamic_vino_lib/src/models/base_model.cpp b/dynamic_vino_lib/src/models/base_model.cpp index 6be8778..2402fb1 100644 --- a/dynamic_vino_lib/src/models/base_model.cpp +++ b/dynamic_vino_lib/src/models/base_model.cpp @@ -38,27 +38,29 @@ Models::BaseModel::BaseModel( throw std::logic_error("model file name is empty!"); } - net_reader_ = std::make_shared<InferenceEngine::CNNNetReader>(); + ///net_reader_ = std::make_shared<InferenceEngine::CNNNetReader>(); } void Models::BaseModel::modelInit() { slog::info << "Loading network files" << slog::endl; // Read network model - net_reader_->ReadNetwork(model_loc_); + ///net_reader_->ReadNetwork(model_loc_); + net_reader_ = engine.ReadNetwork(model_loc_); // Extract model name and load it's weights // remove extension size_t last_index = model_loc_.find_last_of("."); std::string raw_name = model_loc_.substr(0, last_index); - std::string bin_file_name = raw_name + ".bin"; - net_reader_->ReadWeights(bin_file_name); + ///std::string bin_file_name = raw_name + ".bin"; + ///net_reader_->ReadWeights(bin_file_name); // Read labels (if any) std::string label_file_name = raw_name + ".labels"; loadLabelsFromFile(label_file_name); // Set batch size to given max_batch_size_ slog::info << "Batch size is set to " << max_batch_size_ << slog::endl; - net_reader_->getNetwork().setBatchSize(max_batch_size_); + ///net_reader_->getNetwork().setBatchSize(max_batch_size_); + net_reader_.setBatchSize(max_batch_size_); updateLayerProperty(net_reader_); } diff --git a/dynamic_vino_lib/src/models/emotion_detection_model.cpp b/dynamic_vino_lib/src/models/emotion_detection_model.cpp index 46b091d..ef43ea1 100644 --- a/dynamic_vino_lib/src/models/emotion_detection_model.cpp +++ b/dynamic_vino_lib/src/models/emotion_detection_model.cpp @@ -29,11 +29,11 @@ Models::EmotionDetectionModel::EmotionDetectionModel( } bool Models::EmotionDetectionModel::updateLayerProperty -(InferenceEngine::CNNNetReader::Ptr net_reader) +(InferenceEngine::CNNNetwork& net_reader) { slog::info << "Checking INPUTs for model " << getModelName() << slog::endl; // set input property - InferenceEngine::InputsDataMap input_info_map(net_reader->getNetwork().getInputsInfo()); + InferenceEngine::InputsDataMap input_info_map(net_reader.getInputsInfo()); if (input_info_map.size() != 1) { slog::warn << "This model seems not Age-Gender-like, which should have only one input," <<" but we got " << std::to_string(input_info_map.size()) << "inputs" @@ -46,34 +46,34 @@ bool Models::EmotionDetectionModel::updateLayerProperty addInputInfo("input", input_info_map.begin()->first); // set output property - InferenceEngine::OutputsDataMap output_info_map(net_reader->getNetwork().getOutputsInfo()); + InferenceEngine::OutputsDataMap output_info_map(net_reader.getOutputsInfo()); if (output_info_map.size() != 1) { // throw std::logic_error("Age/Gender Recognition network should have two output layers"); slog::warn << "This model should have and only have 1 output, but we got " << std::to_string(output_info_map.size()) << "outputs" << slog::endl; return false; } - InferenceEngine::DataPtr & output_data_ptr = output_info_map.begin()->second; - slog::info << "Emotions layer: " << output_data_ptr->getCreatorLayer().lock()->name << - slog::endl; - output_data_ptr->setPrecision(InferenceEngine::Precision::FP32); - output_data_ptr->setLayout(InferenceEngine::Layout::NCHW); + ///InferenceEngine::DataPtr & output_data_ptr = output_info_map.begin()->second; + ///slog::info << "Emotions layer: " << output_data_ptr->getCreatorLayer().lock()->name << + /// slog::endl; + ///output_data_ptr->setPrecision(InferenceEngine::Precision::FP32); + ///output_data_ptr->setLayout(InferenceEngine::Layout::NCHW); addOutputInfo("output", output_info_map.begin()->first); printAttribute(); - return verifyOutputLayer(output_data_ptr); + return true; ///verifyOutputLayer(output_data_ptr); } bool Models::EmotionDetectionModel::verifyOutputLayer(const InferenceEngine::DataPtr & ptr) { - if (ptr->getCreatorLayer().lock()->type != "SoftMax") { - slog::err <<"In Emotion network, gender layer (" - << ptr->getCreatorLayer().lock()->name - << ") should be a SoftMax, but was: " - << ptr->getCreatorLayer().lock()->type - << slog::endl; - return false; - } +/// if (ptr->getCreatorLayer().lock()->type != "SoftMax") { +/// slog::err <<"In Emotion network, gender layer (" +/// << ptr->getCreatorLayer().lock()->name +/// << ") should be a SoftMax, but was: " +/// << ptr->getCreatorLayer().lock()->type +/// << slog::endl; +/// return false; +/// } return true; } diff --git a/dynamic_vino_lib/src/models/face_reidentification_model.cpp b/dynamic_vino_lib/src/models/face_reidentification_model.cpp index 838b324..94eafa5 100644 --- a/dynamic_vino_lib/src/models/face_reidentification_model.cpp +++ b/dynamic_vino_lib/src/models/face_reidentification_model.cpp @@ -25,17 +25,17 @@ Models::FaceReidentificationModel::FaceReidentificationModel( : BaseModel(model_loc, max_batch_size) {} void Models::FaceReidentificationModel::setLayerProperty( - InferenceEngine::CNNNetReader::Ptr net_reader) + InferenceEngine::CNNNetwork& net_reader) { // set input property InferenceEngine::InputsDataMap input_info_map( - net_reader->getNetwork().getInputsInfo()); + net_reader.getInputsInfo()); InferenceEngine::InputInfo::Ptr input_info = input_info_map.begin()->second; input_info->setPrecision(InferenceEngine::Precision::U8); input_info->getInputData()->setLayout(InferenceEngine::Layout::NCHW); // set output property InferenceEngine::OutputsDataMap output_info_map( - net_reader->getNetwork().getOutputsInfo()); + net_reader.getOutputsInfo()); InferenceEngine::DataPtr & output_data_ptr = output_info_map.begin()->second; output_data_ptr->setPrecision(InferenceEngine::Precision::FP32); output_data_ptr->setLayout(InferenceEngine::Layout::NCHW); @@ -45,7 +45,7 @@ void Models::FaceReidentificationModel::setLayerProperty( } void Models::FaceReidentificationModel::checkLayerProperty( - const InferenceEngine::CNNNetReader::Ptr & net_reader) {} + const InferenceEngine::CNNNetwork & net_reader) {} const std::string Models::FaceReidentificationModel::getModelCategory() const { diff --git a/dynamic_vino_lib/src/models/head_pose_detection_model.cpp b/dynamic_vino_lib/src/models/head_pose_detection_model.cpp index f5e087a..8dad21a 100644 --- a/dynamic_vino_lib/src/models/head_pose_detection_model.cpp +++ b/dynamic_vino_lib/src/models/head_pose_detection_model.cpp @@ -31,11 +31,11 @@ Models::HeadPoseDetectionModel::HeadPoseDetectionModel( } bool Models::HeadPoseDetectionModel::updateLayerProperty -(InferenceEngine::CNNNetReader::Ptr net_reader) +(InferenceEngine::CNNNetwork& net_reader) { slog::info << "Checking INPUTs for model " << getModelName() << slog::endl; // set input property - InferenceEngine::InputsDataMap input_info_map(net_reader->getNetwork().getInputsInfo()); + InferenceEngine::InputsDataMap input_info_map(net_reader.getInputsInfo()); if (input_info_map.size() != 1) { slog::warn << "This model should have only one input, but we got" << std::to_string(input_info_map.size()) << "inputs" @@ -48,7 +48,7 @@ bool Models::HeadPoseDetectionModel::updateLayerProperty addInputInfo("input", input_info_map.begin()->first); // set output property - InferenceEngine::OutputsDataMap output_info_map(net_reader->getNetwork().getOutputsInfo()); + InferenceEngine::OutputsDataMap output_info_map(net_reader.getOutputsInfo()); for (auto & output : output_info_map) { output.second->setPrecision(InferenceEngine::Precision::FP32); output.second->setLayout(InferenceEngine::Layout::NC); diff --git a/dynamic_vino_lib/src/models/landmarks_detection_model.cpp b/dynamic_vino_lib/src/models/landmarks_detection_model.cpp index 6f79968..148559c 100644 --- a/dynamic_vino_lib/src/models/landmarks_detection_model.cpp +++ b/dynamic_vino_lib/src/models/landmarks_detection_model.cpp @@ -25,17 +25,17 @@ Models::LandmarksDetectionModel::LandmarksDetectionModel( : BaseModel(model_loc, max_batch_size) {} void Models::LandmarksDetectionModel::setLayerProperty( - InferenceEngine::CNNNetReader::Ptr net_reader) + InferenceEngine::CNNNetwork& net_reader) { // set input property InferenceEngine::InputsDataMap input_info_map( - net_reader->getNetwork().getInputsInfo()); + net_reader.getInputsInfo()); InferenceEngine::InputInfo::Ptr input_info = input_info_map.begin()->second; input_info->setPrecision(InferenceEngine::Precision::U8); input_info->getInputData()->setLayout(InferenceEngine::Layout::NCHW); // set output property InferenceEngine::OutputsDataMap output_info_map( - net_reader->getNetwork().getOutputsInfo()); + net_reader.getOutputsInfo()); InferenceEngine::DataPtr & output_data_ptr = output_info_map.begin()->second; output_data_ptr->setPrecision(InferenceEngine::Precision::FP32); output_data_ptr->setLayout(InferenceEngine::Layout::NCHW); diff --git a/dynamic_vino_lib/src/models/license_plate_detection_model.cpp b/dynamic_vino_lib/src/models/license_plate_detection_model.cpp index c94e464..896d35f 100644 --- a/dynamic_vino_lib/src/models/license_plate_detection_model.cpp +++ b/dynamic_vino_lib/src/models/license_plate_detection_model.cpp @@ -25,11 +25,11 @@ Models::LicensePlateDetectionModel::LicensePlateDetectionModel( : BaseModel(model_loc, max_batch_size) {} bool Models::LicensePlateDetectionModel::updateLayerProperty( - const InferenceEngine::CNNNetReader::Ptr net_reader) + InferenceEngine::CNNNetwork& net_reader) { slog::info << "Checking INPUTs for model " << getModelName() << slog::endl; InferenceEngine::InputsDataMap input_info_map( - net_reader->getNetwork().getInputsInfo()); + net_reader.getInputsInfo()); if (input_info_map.size() != 2) { throw std::logic_error("Vehicle Attribs topology should have only two inputs"); } @@ -38,7 +38,7 @@ bool Models::LicensePlateDetectionModel::updateLayerProperty( throw std::logic_error("License plate detection max sequence size dismatch"); } InferenceEngine::OutputsDataMap output_info_map( - net_reader->getNetwork().getOutputsInfo()); + net_reader.getOutputsInfo()); if (output_info_map.size() != 1) { throw std::logic_error("Vehicle Attribs Network expects networks having one output"); } diff --git a/dynamic_vino_lib/src/models/object_detection_ssd_model.cpp b/dynamic_vino_lib/src/models/object_detection_ssd_model.cpp index 71bb68e..949deeb 100644 --- a/dynamic_vino_lib/src/models/object_detection_ssd_model.cpp +++ b/dynamic_vino_lib/src/models/object_detection_ssd_model.cpp @@ -148,11 +148,11 @@ bool Models::ObjectDetectionSSDModel::fetchResults( } bool Models::ObjectDetectionSSDModel::updateLayerProperty( - const InferenceEngine::CNNNetReader::Ptr net_reader) + InferenceEngine::CNNNetwork& net_reader) { slog::info << "Checking INPUTs for model " << getModelName() << slog::endl; - InferenceEngine::InputsDataMap input_info_map(net_reader->getNetwork().getInputsInfo()); + InferenceEngine::InputsDataMap input_info_map(net_reader.getInputsInfo()); if (input_info_map.size() != 1) { slog::warn << "This model seems not SSDNet-like, SSDnet has only one input, but we got " << std::to_string(input_info_map.size()) << "inputs" << slog::endl; @@ -168,7 +168,7 @@ bool Models::ObjectDetectionSSDModel::updateLayerProperty( setInputWidth(input_dims[3]); slog::info << "Checking OUTPUTs for model " << getModelName() << slog::endl; - InferenceEngine::OutputsDataMap output_info_map(net_reader->getNetwork().getOutputsInfo()); + InferenceEngine::OutputsDataMap output_info_map(net_reader.getOutputsInfo()); if (output_info_map.size() != 1) { slog::warn << "This model seems not SSDNet-like! We got " << std::to_string(output_info_map.size()) << "outputs, but SSDnet has only one." @@ -182,6 +182,7 @@ bool Models::ObjectDetectionSSDModel::updateLayerProperty( output_data_ptr->setPrecision(InferenceEngine::Precision::FP32); ///TODO: double check this part: BEGIN +#if(0) const InferenceEngine::CNNLayerPtr output_layer = net_reader->getNetwork().getLayerByName(output_info_map.begin()->first.c_str()); // output layer should have attribute called num_classes @@ -194,6 +195,7 @@ bool Models::ObjectDetectionSSDModel::updateLayerProperty( // class number should be equal to size of label vector // if network has default "background" class, fake is used const int num_classes = output_layer->GetParamAsInt("num_classes"); +#endif #if 0 slog::info << "Checking Object Detection output ... num_classes=" << num_classes << slog::endl; if (getLabels().size() != num_classes) { diff --git a/dynamic_vino_lib/src/models/object_detection_yolov2_model.cpp b/dynamic_vino_lib/src/models/object_detection_yolov2_model.cpp index 1e8d26c..1c86020 100644 --- a/dynamic_vino_lib/src/models/object_detection_yolov2_model.cpp +++ b/dynamic_vino_lib/src/models/object_detection_yolov2_model.cpp @@ -34,11 +34,11 @@ Models::ObjectDetectionYolov2Model::ObjectDetectionYolov2Model( } bool Models::ObjectDetectionYolov2Model::updateLayerProperty( - const InferenceEngine::CNNNetReader::Ptr net_reader) + InferenceEngine::CNNNetwork& net_reader) { slog::info << "Checking INPUTs for model " << getModelName() << slog::endl; - InferenceEngine::InputsDataMap input_info_map(net_reader->getNetwork().getInputsInfo()); + InferenceEngine::InputsDataMap input_info_map(net_reader.getInputsInfo()); if (input_info_map.size() != 1) { slog::warn << "This model seems not Yolo-like, which has only one input, but we got " << std::to_string(input_info_map.size()) << "inputs" << slog::endl; @@ -52,7 +52,7 @@ bool Models::ObjectDetectionYolov2Model::updateLayerProperty( addInputInfo("input", input_info_map.begin()->first); // set output property - InferenceEngine::OutputsDataMap output_info_map(net_reader->getNetwork().getOutputsInfo()); + InferenceEngine::OutputsDataMap output_info_map(net_reader.getOutputsInfo()); if (output_info_map.size() != 1) { slog::warn << "This model seems not Yolo-like! We got " << std::to_string(output_info_map.size()) << "outputs, but SSDnet has only one." @@ -65,6 +65,7 @@ bool Models::ObjectDetectionYolov2Model::updateLayerProperty( slog::info << "Checking Object Detection output ... Name=" << output_info_map.begin()->first << slog::endl; +#if(0) /// const InferenceEngine::CNNLayerPtr output_layer = net_reader->getNetwork().getLayerByName(output_info_map.begin()->first.c_str()); // output layer should have attribute called num_classes @@ -86,6 +87,7 @@ bool Models::ObjectDetectionYolov2Model::updateLayerProperty( getLabels().clear(); } } +#endif // last dimension of output layer should be 7 const InferenceEngine::SizeVector output_dims = output_data_ptr->getTensorDesc().getDims(); @@ -226,19 +228,19 @@ bool Models::ObjectDetectionYolov2Model::fetchResults( const float * detections = request->GetBlob(output)->buffer().as<InferenceEngine::PrecisionTrait <InferenceEngine::Precision::FP32>::value_type *>(); - InferenceEngine::CNNLayerPtr layer = - getNetReader()->getNetwork().getLayerByName(output.c_str()); + ///InferenceEngine::CNNLayerPtr layer = + /// getNetReader()->getNetwork().getLayerByName(output.c_str()); int input_height = input_info_->getTensorDesc().getDims()[2]; int input_width = input_info_->getTensorDesc().getDims()[3]; // --------------------------- Validating output parameters -------------------------------- - if (layer != nullptr && layer->type != "RegionYolo") { - throw std::runtime_error("Invalid output type: " + layer->type + ". RegionYolo expected"); - } + ///if (layer != nullptr && layer->type != "RegionYolo") { + /// throw std::runtime_error("Invalid output type: " + layer->type + ". RegionYolo expected"); + ///} // --------------------------- Extracting layer parameters -------------------------------- - const int num = layer->GetParamAsInt("num"); - const int coords = layer->GetParamAsInt("coords"); - const int classes = layer->GetParamAsInt("classes"); + const int num = 3; ///layer->GetParamAsInt("num"); + const int coords = 9; ///layer->GetParamAsInt("coords"); + const int classes = 21; ///layer->GetParamAsInt("classes"); auto blob = request->GetBlob(output); const int out_blob_h = static_cast<int>(blob->getTensorDesc().getDims()[2]);; diff --git a/dynamic_vino_lib/src/models/object_segmentation_model.cpp b/dynamic_vino_lib/src/models/object_segmentation_model.cpp index b83eb33..c64baff 100644 --- a/dynamic_vino_lib/src/models/object_segmentation_model.cpp +++ b/dynamic_vino_lib/src/models/object_segmentation_model.cpp @@ -109,11 +109,11 @@ const std::string Models::ObjectSegmentationModel::getModelCategory() const } bool Models::ObjectSegmentationModel::updateLayerProperty( - const InferenceEngine::CNNNetReader::Ptr net_reader) + InferenceEngine::CNNNetwork& net_reader) { slog::info<< "Checking INPUTS for Model" <<getModelName()<<slog::endl; - auto network = net_reader->getNetwork(); + auto network = net_reader; input_info_ = InferenceEngine::InputsDataMap(network.getInputsInfo()); InferenceEngine::ICNNNetwork:: InputShapes inputShapes = network.getInputShapes(); @@ -193,8 +193,8 @@ bool Models::ObjectSegmentationModel::updateLayerProperty( //const InferenceEngine::CNNLayerPtr output_layer = //network.getLayerByName(outputsDataMap.begin()->first.c_str()); - const InferenceEngine::CNNLayerPtr output_layer = - network.getLayerByName(getOutputName("detection").c_str()); + ///const InferenceEngine::CNNLayerPtr output_layer = + /// network.getLayerByName(getOutputName("detection").c_str()); //const int num_classes = output_layer->GetParamAsInt("num_classes"); //slog::info << "Checking Object Segmentation output ... num_classes=" << num_classes << slog::endl; diff --git a/dynamic_vino_lib/src/models/person_attribs_detection_model.cpp b/dynamic_vino_lib/src/models/person_attribs_detection_model.cpp index 3537ae4..355b285 100644 --- a/dynamic_vino_lib/src/models/person_attribs_detection_model.cpp +++ b/dynamic_vino_lib/src/models/person_attribs_detection_model.cpp @@ -25,11 +25,11 @@ Models::PersonAttribsDetectionModel::PersonAttribsDetectionModel( : BaseModel(model_loc, max_batch_size) {} bool Models::PersonAttribsDetectionModel::updateLayerProperty( - InferenceEngine::CNNNetReader::Ptr net_reader) + InferenceEngine::CNNNetwork& net_reader) { slog::info << "Checking INPUTs for model " << getModelName() << slog::endl; InferenceEngine::InputsDataMap input_info_map( - net_reader->getNetwork().getInputsInfo()); + net_reader.getInputsInfo()); if (input_info_map.size() != 1) { throw std::logic_error("Person Attribs topology should have only one input"); } @@ -40,7 +40,7 @@ bool Models::PersonAttribsDetectionModel::updateLayerProperty( slog::info << "Checking OUTPUTs for model " << getModelName() << slog::endl; InferenceEngine::OutputsDataMap output_info_map( - net_reader->getNetwork().getOutputsInfo()); + net_reader.getOutputsInfo()); if (output_info_map.size() != 3) { throw std::logic_error("Person Attribs Network expects networks having 3 output"); } diff --git a/dynamic_vino_lib/src/models/person_reidentification_model.cpp b/dynamic_vino_lib/src/models/person_reidentification_model.cpp index 249f978..7ae2410 100644 --- a/dynamic_vino_lib/src/models/person_reidentification_model.cpp +++ b/dynamic_vino_lib/src/models/person_reidentification_model.cpp @@ -50,11 +50,11 @@ const std::string Models::PersonReidentificationModel::getModelCategory() const } */ bool Models::PersonReidentificationModel::updateLayerProperty( - InferenceEngine::CNNNetReader::Ptr netreader) + InferenceEngine::CNNNetwork& netreader) { slog::info << "Checking Inputs for Model" << getModelName() << slog::endl; - auto network = netreader->getNetwork(); + auto network = netreader; InferenceEngine::InputsDataMap input_info_map(network.getInputsInfo()); diff --git a/dynamic_vino_lib/src/models/vehicle_attribs_detection_model.cpp b/dynamic_vino_lib/src/models/vehicle_attribs_detection_model.cpp index ce58d23..1cdf68b 100644 --- a/dynamic_vino_lib/src/models/vehicle_attribs_detection_model.cpp +++ b/dynamic_vino_lib/src/models/vehicle_attribs_detection_model.cpp @@ -25,17 +25,17 @@ Models::VehicleAttribsDetectionModel::VehicleAttribsDetectionModel( : BaseModel(model_loc, max_batch_size) {} bool Models::VehicleAttribsDetectionModel::updateLayerProperty( - InferenceEngine::CNNNetReader::Ptr net_reader) + InferenceEngine::CNNNetwork& net_reader) { slog::info << "Checking INPUTs for model " << getModelName() << slog::endl; // set input property InferenceEngine::InputsDataMap input_info_map( - net_reader->getNetwork().getInputsInfo()); + net_reader.getInputsInfo()); if (input_info_map.size() != 1) { throw std::logic_error("Vehicle Attribs topology should have only one input"); } InferenceEngine::OutputsDataMap output_info_map( - net_reader->getNetwork().getOutputsInfo()); + net_reader.getOutputsInfo()); if (output_info_map.size() != 2) { throw std::logic_error("Vehicle Attribs Network expects networks having two outputs"); } openvino@openvino-RQT37:~/my_ros2_ws/src/ros2_openvino_toolkit$ ``` github pull request https://gitbook.tw/chapters/github/pull-request.html