From 21c34b45a932d6b5da8e7b914da2da7ae2a31a0f Mon Sep 17 00:00:00 2001 From: luyang00 <393780933@qq.com> Date: Thu, 7 Mar 2019 13:25:31 +0800 Subject: [PATCH 01/15] add support for object segmentation --- dynamic_vino_lib/CMakeLists.txt | 2 + .../inferences/object_segmentation.h | 131 +++++++++++++++ .../models/object_segmentation_model.h | 72 ++++++++ .../dynamic_vino_lib/outputs/base_output.h | 7 + .../outputs/image_window_output.h | 20 ++- .../dynamic_vino_lib/pipeline_manager.h | 3 +- .../src/inferences/object_segmentation.cpp | 154 ++++++++++++++++++ .../src/models/object_segmentation_model.cpp | 76 +++++++++ .../src/outputs/image_window_output.cpp | 55 +++++++ dynamic_vino_lib/src/pipeline_manager.cpp | 23 +++ sample/src/pipeline_with_params.cpp | 3 +- vino_launch/param/pipeline_segmentation.yaml | 19 +++ 12 files changed, 562 insertions(+), 3 deletions(-) create mode 100644 dynamic_vino_lib/include/dynamic_vino_lib/inferences/object_segmentation.h create mode 100644 dynamic_vino_lib/include/dynamic_vino_lib/models/object_segmentation_model.h create mode 100644 dynamic_vino_lib/src/inferences/object_segmentation.cpp create mode 100644 dynamic_vino_lib/src/models/object_segmentation_model.cpp create mode 100644 vino_launch/param/pipeline_segmentation.yaml diff --git a/dynamic_vino_lib/CMakeLists.txt b/dynamic_vino_lib/CMakeLists.txt index 67e5d8d1..e1d04721 100644 --- a/dynamic_vino_lib/CMakeLists.txt +++ b/dynamic_vino_lib/CMakeLists.txt @@ -144,6 +144,7 @@ add_library(${PROJECT_NAME} SHARED src/inferences/face_detection.cpp src/inferences/head_pose_detection.cpp src/inferences/object_detection.cpp + src/inferences/object_segmentation.cpp src/inputs/realsense_camera.cpp src/inputs/realsense_camera_topic.cpp src/inputs/standard_camera.cpp @@ -155,6 +156,7 @@ add_library(${PROJECT_NAME} SHARED src/models/face_detection_model.cpp src/models/head_pose_detection_model.cpp src/models/object_detection_model.cpp + src/models/object_segmentation_model.cpp src/outputs/image_window_output.cpp src/outputs/ros_topic_output.cpp src/outputs/rviz_output.cpp diff --git a/dynamic_vino_lib/include/dynamic_vino_lib/inferences/object_segmentation.h b/dynamic_vino_lib/include/dynamic_vino_lib/inferences/object_segmentation.h new file mode 100644 index 00000000..e6100e1a --- /dev/null +++ b/dynamic_vino_lib/include/dynamic_vino_lib/inferences/object_segmentation.h @@ -0,0 +1,131 @@ +// Copyright (c) 2018 Intel Corporation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/** + * @brief A header file with declaration for ObjectSegmentation Class + * @file object_detection.hpp + */ +#ifndef DYNAMIC_VINO_LIB__INFERENCES__OBJECT_SEGMENTATION_HPP_ +#define DYNAMIC_VINO_LIB__INFERENCES__OBJECT_SEGMENTATION_HPP_ +#include +#include +#include +#include +#include +#include +#include "dynamic_vino_lib/models/object_segmentation_model.h" +#include "dynamic_vino_lib/engines/engine.h" +#include "dynamic_vino_lib/inferences/base_inference.h" +#include "inference_engine.hpp" +#include "opencv2/opencv.hpp" +// namespace +namespace dynamic_vino_lib +{ +/** + * @class ObjectSegmentationResult + * @brief Class for storing and processing object segmentation result. + */ +class ObjectSegmentationResult : public Result +{ +public: + friend class ObjectSegmentation; + explicit ObjectSegmentationResult(const cv::Rect & location); + std::string getLabel() const + { + return label_; + } + /** + * @brief Get the confidence that the detected area is a face. + * @return The confidence value. + */ + float getConfidence() const + { + return confidence_; + } + cv::Mat getMask() const + { + return mask_; + } + +private: + std::string label_ = ""; + float confidence_ = -1; + cv::Mat mask_; +}; +/** + * @class ObjectSegmentation + * @brief Class to load object segmentation model and perform object segmentation. + */ +class ObjectSegmentation : public BaseInference +{ +public: + using Result = dynamic_vino_lib::ObjectSegmentationResult; + explicit ObjectSegmentation(double); + ~ObjectSegmentation() override; + /** + * @brief Load the object segmentation model. + */ + void loadNetwork(std::shared_ptr); + /** + * @brief Enqueue a frame to this class. + * The frame will be buffered but not infered yet. + * @param[in] frame The frame to be enqueued. + * @param[in] input_frame_loc The location of the enqueued frame with respect + * to the frame generated by the input device. + * @return Whether this operation is successful. + */ + bool enqueue(const cv::Mat &, const cv::Rect &) override; + /** + * @brief Start inference for all buffered frames. + * @return Whether this operation is successful. + */ + bool submitRequest() override; + /** + * @brief This function will fetch the results of the previous inference and + * stores the results in a result buffer array. All buffered frames will be + * cleared. + * @return Whether the Inference object fetches a result this time + */ + bool fetchResults() override; + /** + * @brief Get the length of the buffer result array. + * @return The length of the buffer result array. + */ + const int getResultsLength() const override; + /** + * @brief Get the location of result with respect + * to the frame generated by the input device. + * @param[in] idx The index of the result. + */ + const dynamic_vino_lib::Result * getLocationResult(int idx) const override; + /** + * @brief Show the observed detection result either through image window + or ROS topic. + */ + const void observeOutput(const std::shared_ptr & output); + /** + * @brief Get the name of the Inference instance. + * @return The name of the Inference instance. + */ + const std::string getName() const override; + +private: + std::shared_ptr valid_model_; + std::vector results_; + int width_ = 0; + int height_ = 0; + double show_output_thresh_ = 0; +}; +} // namespace dynamic_vino_lib +#endif // DYNAMIC_VINO_LIB__INFERENCES__OBJECT_SEGMENTATION_HPP_ diff --git a/dynamic_vino_lib/include/dynamic_vino_lib/models/object_segmentation_model.h b/dynamic_vino_lib/include/dynamic_vino_lib/models/object_segmentation_model.h new file mode 100644 index 00000000..38418824 --- /dev/null +++ b/dynamic_vino_lib/include/dynamic_vino_lib/models/object_segmentation_model.h @@ -0,0 +1,72 @@ +// Copyright (c) 2018 Intel Corporation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +/** + * @brief A header file with declaration for ObjectSegmentationModel Class + * @file face_detection_model.h + */ +#ifndef DYNAMIC_VINO_LIB__MODELS__OBJECT_SEGMENTATION_MODEL_HPP_ +#define DYNAMIC_VINO_LIB__MODELS__OBJECT_SEGMENTATION_MODEL_HPP_ +#include +#include "dynamic_vino_lib/models/base_model.h" +namespace Models +{ +/** + * @class ObjectSegmentationModel + * @brief This class generates the object segmentation model. + */ +class ObjectSegmentationModel : public BaseModel +{ +public: + ObjectSegmentationModel(const std::string &, int, int, int); + inline const int getMaxProposalCount() + { + return max_proposal_count_; + } + inline const int getObjectSize() + { + return object_size_; + } + inline const std::string getInputName() + { + return input_; + } + inline const std::string getDetectionOutputName() + { + return detection_output_; + } + inline const std::string getMaskOutputName() + { + return mask_output_; + } + + /** + * @brief Get the name of this segmentation model. + * @return Name of the model. + */ + const std::string getModelName() const override; + +protected: + void checkLayerProperty(const InferenceEngine::CNNNetReader::Ptr &) override; + void setLayerProperty(InferenceEngine::CNNNetReader::Ptr) override; + //void checkNetworkSize(int input_size, int output_size, InferenceEngine::CNNNetReader::Ptr net_reader) override; + +private: + int max_proposal_count_; + int object_size_; + std::string input_; + std::string mask_output_; + std::string detection_output_; +}; +} // namespace Models +#endif // DYNAMIC_VINO_LIB__MODELS__OBJECT_SEGMENTATION_MODEL_HPP_ diff --git a/dynamic_vino_lib/include/dynamic_vino_lib/outputs/base_output.h b/dynamic_vino_lib/include/dynamic_vino_lib/outputs/base_output.h index 45f18b2c..50bd2dd9 100644 --- a/dynamic_vino_lib/include/dynamic_vino_lib/outputs/base_output.h +++ b/dynamic_vino_lib/include/dynamic_vino_lib/outputs/base_output.h @@ -31,6 +31,7 @@ #include "dynamic_vino_lib/inferences/face_detection.h" #include "dynamic_vino_lib/inferences/head_pose_detection.h" #include "dynamic_vino_lib/inferences/object_detection.h" +#include "dynamic_vino_lib/inferences/object_segmentation.h" #include "opencv2/opencv.hpp" class Pipeline; @@ -82,6 +83,12 @@ class BaseOutput virtual void accept(const std::vector&) { } + /** + * @brief Generate output content according to the object segmentation result. + */ + virtual void accept(const std::vector&) + { + } /** * @brief Calculate the camera matrix of a frame for image window output, no implementation for ros topic output. diff --git a/dynamic_vino_lib/include/dynamic_vino_lib/outputs/image_window_output.h b/dynamic_vino_lib/include/dynamic_vino_lib/outputs/image_window_output.h index 91cdcb92..161a0c2b 100644 --- a/dynamic_vino_lib/include/dynamic_vino_lib/outputs/image_window_output.h +++ b/dynamic_vino_lib/include/dynamic_vino_lib/outputs/image_window_output.h @@ -83,7 +83,18 @@ class ImageWindowOutput : public BaseOutput * @param[in] An object detection result objetc. */ void accept(const std::vector&) override; - + /** + * @brief Generate image window output content according to + * the object segmentation result. + * @param[in] An object segmentation result objetc. + */ + void accept(const std::vector&) override; + /** + * @brief Merge mask for image window ouput + * the object segmentation result. + * @param[in] An object segmentation result objetc. + */ + void mergeMask(const std::vector &); private: void initOutputs(unsigned size); @@ -116,6 +127,13 @@ class ImageWindowOutput : public BaseOutput const std::string window_name_; float focal_length_; cv::Mat camera_matrix_; + std::vector> colors_ = { + {128, 64, 128}, {232, 35, 244}, {70, 70, 70}, {156, 102, 102}, {153, 153, 190}, + {153, 153, 153}, {30, 170, 250}, {0, 220, 220}, {35, 142, 107}, {152, 251, 152}, + {180, 130, 70}, {60, 20, 220}, {0, 0, 255}, {142, 0, 0}, {70, 0, 0}, + {100, 60, 0}, {90, 0, 0}, {230, 0, 0}, {32, 11, 119}, {0, 74, 111}, + {81, 0, 81} + }; }; } // namespace Outputs #endif // DYNAMIC_VINO_LIB_OUTPUTS_IMAGE_WINDOW_OUTPUT_H diff --git a/dynamic_vino_lib/include/dynamic_vino_lib/pipeline_manager.h b/dynamic_vino_lib/include/dynamic_vino_lib/pipeline_manager.h index f169dee4..33af6678 100644 --- a/dynamic_vino_lib/include/dynamic_vino_lib/pipeline_manager.h +++ b/dynamic_vino_lib/include/dynamic_vino_lib/pipeline_manager.h @@ -94,7 +94,8 @@ class PipelineManager { const Params::ParamManager::InferenceParams& infer); std::shared_ptr createObjectDetection( const Params::ParamManager::InferenceParams& infer); - + std::shared_ptr createObjectSegmentation( + const Params::ParamManager::InferenceParams& infer); std::map pipelines_; std::map plugins_for_devices_; }; diff --git a/dynamic_vino_lib/src/inferences/object_segmentation.cpp b/dynamic_vino_lib/src/inferences/object_segmentation.cpp new file mode 100644 index 00000000..69b7fd23 --- /dev/null +++ b/dynamic_vino_lib/src/inferences/object_segmentation.cpp @@ -0,0 +1,154 @@ +// Copyright (c) 2018 Intel Corporation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/** + * @brief a header file with declaration of ObjectSegmentation class and + * ObjectSegmentationResult class + * @file object_segmentation.cpp + */ +#include +#include +#include +#include + +#include "dynamic_vino_lib/inferences/object_segmentation.h" +#include "dynamic_vino_lib/outputs/base_output.h" +#include "dynamic_vino_lib/slog.h" + +// ObjectSegmentationResult +dynamic_vino_lib::ObjectSegmentationResult::ObjectSegmentationResult(const cv::Rect & location) +: Result(location) +{ +} + +// ObjectSegmentation +dynamic_vino_lib::ObjectSegmentation::ObjectSegmentation(double show_output_thresh) +: show_output_thresh_(show_output_thresh), dynamic_vino_lib::BaseInference() +{ +} + +dynamic_vino_lib::ObjectSegmentation::~ObjectSegmentation() = default; + +void dynamic_vino_lib::ObjectSegmentation::loadNetwork( + const std::shared_ptr network) +{ + valid_model_ = network; + setMaxBatchSize(network->getMaxBatchSize()); +} + +bool dynamic_vino_lib::ObjectSegmentation::enqueue( + const cv::Mat & frame, + const cv::Rect & input_frame_loc) +{ + if (width_ == 0 && height_ == 0) { + width_ = frame.cols; + height_ = frame.rows; + } + if (!dynamic_vino_lib::BaseInference::enqueue(frame, input_frame_loc, 1, 0, + valid_model_->getInputName())) + { + return false; + } + Result r(input_frame_loc); + results_.clear(); + results_.emplace_back(r); + return true; +} + +bool dynamic_vino_lib::ObjectSegmentation::submitRequest() +{ + return dynamic_vino_lib::BaseInference::submitRequest(); +} + +bool dynamic_vino_lib::ObjectSegmentation::fetchResults() +{ + bool can_fetch = dynamic_vino_lib::BaseInference::fetchResults(); + if (!can_fetch) { + return false; + } + bool found_result = false; + results_.clear(); + InferenceEngine::InferRequest::Ptr request = getEngine()->getRequest(); + std::string detection_output = valid_model_->getDetectionOutputName(); + std::string mask_output = valid_model_->getMaskOutputName(); + const auto do_blob = request->GetBlob(detection_output.c_str()); + const auto do_data = do_blob->buffer().as(); + const auto masks_blob = request->GetBlob(mask_output.c_str()); + const auto masks_data = masks_blob->buffer().as(); + // amount of elements in each detected box description (batch, label, prob, x1, y1, x2, y2) + size_t box_num = masks_blob->dims().at(3); + size_t label_num = masks_blob->dims().at(2); + size_t box_description_size = do_blob->dims().at(0); + size_t H = masks_blob->dims().at(1); + size_t W = masks_blob->dims().at(0); + size_t box_stride = W * H * label_num; + for (size_t box = 0; box < box_num; ++box) { + float * box_info = do_data + box * box_description_size; + float batch = box_info[0]; + if (batch < 0) { + break; + } + float prob = box_info[2]; + if (prob > show_output_thresh_) { + float x1 = std::min(std::max(0.0f, box_info[3] * width_), static_cast(width_)); + float y1 = std::min(std::max(0.0f, box_info[4] * height_), static_cast(height_)); + float x2 = std::min(std::max(0.0f, box_info[5] * width_), static_cast(width_)); + float y2 = std::min(std::max(0.0f, box_info[6] * height_), static_cast(height_)); + int box_width = std::min(static_cast(std::max(0.0f, x2 - x1)), width_); + int box_height = std::min(static_cast(std::max(0.0f, y2 - y1)), height_); + int class_id = static_cast(box_info[1] + 1e-6f); + float * mask_arr = masks_data + box_stride * box + H * W * (class_id - 1); + cv::Mat mask_mat(H, W, CV_32FC1, mask_arr); + cv::Rect roi = cv::Rect(static_cast(x1), static_cast(y1), box_width, box_height); + cv::Mat resized_mask_mat(box_height, box_width, CV_32FC1); + cv::resize(mask_mat, resized_mask_mat, cv::Size(box_width, box_height)); + Result result(roi); + result.confidence_ = prob; + std::vector & labels = valid_model_->getLabels(); + result.label_ = class_id < labels.size() ? labels[class_id] : + std::string("label #") + std::to_string(class_id); + result.mask_ = resized_mask_mat; + found_result = true; + results_.emplace_back(result); + } + } + if (!found_result) { + results_.clear(); + } + return true; +} + +const int dynamic_vino_lib::ObjectSegmentation::getResultsLength() const +{ + return static_cast(results_.size()); +} + +const dynamic_vino_lib::Result * +dynamic_vino_lib::ObjectSegmentation::getLocationResult(int idx) const +{ + return &(results_[idx]); +} + +const std::string dynamic_vino_lib::ObjectSegmentation::getName() const +{ + return valid_model_->getModelName(); +} + +const void dynamic_vino_lib::ObjectSegmentation::observeOutput( + const std::shared_ptr & output) +{ + if (output != nullptr) { + output->accept(results_); + } +} diff --git a/dynamic_vino_lib/src/models/object_segmentation_model.cpp b/dynamic_vino_lib/src/models/object_segmentation_model.cpp new file mode 100644 index 00000000..2feb29c7 --- /dev/null +++ b/dynamic_vino_lib/src/models/object_segmentation_model.cpp @@ -0,0 +1,76 @@ +// Copyright (c) 2018 Intel Corporation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/** + * @brief a header file with declaration of ObjectSegmentationModel class + * @file object_detection_model.cpp + */ +#include +#include "dynamic_vino_lib/models/object_segmentation_model.h" +#include "dynamic_vino_lib/slog.h" +// Validated Object Detection Network +Models::ObjectSegmentationModel::ObjectSegmentationModel( + const std::string & model_loc, + int input_num, int output_num, + int max_batch_size) +: BaseModel(model_loc, input_num, output_num, max_batch_size) +{ +} + +void Models::ObjectSegmentationModel::setLayerProperty( + InferenceEngine::CNNNetReader::Ptr net_reader) +{ + // set input property + InferenceEngine::InputsDataMap input_info_map(net_reader->getNetwork().getInputsInfo()); + auto inputInfoItem = *input_info_map.begin(); + inputInfoItem.second->setPrecision(InferenceEngine::Precision::U8); + auto network = net_reader->getNetwork(); + try { + network.addOutput(std::string("detection_output"), 0); + } catch (std::exception & error) { + throw std::logic_error(getModelName() + "is failed when adding detection_output laryer."); + } + network.setBatchSize(1); + slog::info << "Batch size is " << std::to_string(net_reader->getNetwork().getBatchSize()) << + slog::endl; + InferenceEngine::OutputsDataMap output_info_map(net_reader->getNetwork().getOutputsInfo()); + for (auto & item : output_info_map) { + item.second->setPrecision(InferenceEngine::Precision::FP32); + } + auto output_ptr = output_info_map.begin(); + input_ = input_info_map.begin()->first; + detection_output_ = output_ptr->first; + mask_output_ = (++output_ptr)->first; +} + +void Models::ObjectSegmentationModel::checkLayerProperty( + const InferenceEngine::CNNNetReader::Ptr & net_reader) +{ + const InferenceEngine::CNNLayerPtr output_layer = + net_reader->getNetwork().getLayerByName("detection_output"); + const int num_classes = output_layer->GetParamAsInt("num_classes"); + slog::info << "Checking Object Segmentation output ... num_classes=" << num_classes << slog::endl; + if (getLabels().size() != num_classes) { + if (getLabels().size() == (num_classes - 1)) { + getLabels().insert(getLabels().begin(), "fake"); + } else { + getLabels().clear(); + } + } +} + +const std::string Models::ObjectSegmentationModel::getModelName() const +{ + return "Object Segmentation"; +} diff --git a/dynamic_vino_lib/src/outputs/image_window_output.cpp b/dynamic_vino_lib/src/outputs/image_window_output.cpp index 9bab9fee..ee6d9fee 100644 --- a/dynamic_vino_lib/src/outputs/image_window_output.cpp +++ b/dynamic_vino_lib/src/outputs/image_window_output.cpp @@ -234,6 +234,61 @@ void Outputs::ImageWindowOutput::accept( } } +void Outputs::ImageWindowOutput::mergeMask( + const std::vector & results) +{ + std::map class_color; + for (unsigned i = 0; i < results.size(); i++) { + std::string class_label = results[i].getLabel(); + if (class_color.find(class_label) == class_color.end()) { + class_color[class_label] = class_color.size(); + } + auto & color = colors_[class_color[class_label]]; + const float alpha = 0.7f; + const float MASK_THRESHOLD = 0.5; + + cv::Rect location = results[i].getLocation(); + cv::Mat roi_img = frame_(location); + cv::Mat mask = results[i].getMask(); + cv::Mat colored_mask(location.height, location.width, frame_.type()); + + for (int h = 0; h < mask.size().height; ++h) { + for (int w = 0; w < mask.size().width; ++w) { + for (int ch = 0; ch < colored_mask.channels(); ++ch) { + colored_mask.at(h, w)[ch] = mask.at(h, w) > MASK_THRESHOLD ? + 255 * color[ch] : + roi_img.at(h, w)[ch]; + } + } + } + cv::addWeighted(colored_mask, alpha, roi_img, 1.0f - alpha, 0.0f, roi_img); + } +} + +void Outputs::ImageWindowOutput::accept( + const std::vector & results) +{ + if (outputs_.size() == 0) { + initOutputs(results.size()); + } + if (outputs_.size() != results.size()) { + slog::err << "the size of Object Segmentation and Output Vector is not equal!" << slog::endl; + return; + } + for (unsigned i = 0; i < results.size(); i++) { + outputs_[i].rect = results[i].getLocation(); + auto fd_conf = results[i].getConfidence(); + if (fd_conf >= 0) { + std::ostringstream ostream; + ostream << "[" << std::fixed << std::setprecision(3) << fd_conf << "]"; + outputs_[i].desc += ostream.str(); + } + auto label = results[i].getLabel(); + outputs_[i].desc += "[" + label + "]"; + } + mergeMask(results); +} + void Outputs::ImageWindowOutput::decorateFrame() { if (getPipeline()->getParameters()->isGetFps()) diff --git a/dynamic_vino_lib/src/pipeline_manager.cpp b/dynamic_vino_lib/src/pipeline_manager.cpp index 4879d41c..f7e4d989 100644 --- a/dynamic_vino_lib/src/pipeline_manager.cpp +++ b/dynamic_vino_lib/src/pipeline_manager.cpp @@ -190,6 +190,13 @@ PipelineManager::parseInference( object = createObjectDetection(infer); } + else if (infer.name == kInferTpye_ObjectSegmentation) { + object = createObjectSegmentation(infer); + } + else { + slog::err << "Invalid inference name: " << infer.name << slog::endl; + } + if (object != nullptr) { inferences.insert({infer.name, object}); @@ -279,6 +286,22 @@ const Params::ParamManager::InferenceParams & infer) return object_inference_ptr; } +std::shared_ptr +PipelineManager::createObjectSegmentation(const Params::ParamManager::InferenceParams & infer) +{ + auto obejct_segmentation_model = + std::make_shared(infer.model, 1, 2, 1); + obejct_segmentation_model->modelInit(); + auto obejct_segmentation_engine = std::make_shared( + plugins_for_devices_[infer.engine], obejct_segmentation_model); + auto segmentation_inference_ptr = std::make_shared(0.5); + segmentation_inference_ptr->loadNetwork(obejct_segmentation_model); + segmentation_inference_ptr->loadEngine(obejct_segmentation_engine); + + return segmentation_inference_ptr; +} + + void PipelineManager::threadPipeline(const char* name) { PipelineData& p = pipelines_[name]; while (p.state == PipelineState_ThreadRunning && p.pipeline != nullptr && ros::ok()) { diff --git a/sample/src/pipeline_with_params.cpp b/sample/src/pipeline_with_params.cpp index 27df404e..7cfd2798 100644 --- a/sample/src/pipeline_with_params.cpp +++ b/sample/src/pipeline_with_params.cpp @@ -76,8 +76,9 @@ int main(int argc, char** argv) { ros::init(argc, argv, "sample_with_params"); + + std::string FLAGS_config; ros::param::param("~param_file", FLAGS_config, "/param/pipeline_people.yaml"); - slog::info << "FLAGS_config=" << FLAGS_config << slog::endl; try diff --git a/vino_launch/param/pipeline_segmentation.yaml b/vino_launch/param/pipeline_segmentation.yaml new file mode 100644 index 00000000..a5540346 --- /dev/null +++ b/vino_launch/param/pipeline_segmentation.yaml @@ -0,0 +1,19 @@ +Pipelines: +- name: segmentation + inputs: [RealSenseCamera] + infers: + - name: ObjectSegmentation + model: /opt/models/mask_rcnn_inception_v2_coco_2018_01_28/output/frozen_inference_graph.xml + engine: CPU + label: to/be/set/xxx.labels + batch: 1 + outputs: [ImageWindow] + confidence_threshold: 0.2 + connects: + - left: RealSenseCamera + right: [ObjectSegmentation] + - left: ObjectSegmentation + right: [ImageWindow] + +OpenvinoCommon: + From 6e8d4b4417957554dfb946b8d14166e0c744adb2 Mon Sep 17 00:00:00 2001 From: luyang00 <393780933@qq.com> Date: Thu, 7 Mar 2019 13:54:38 +0800 Subject: [PATCH 02/15] fix launch parameters from 'sample/param/xxxx.yaml' --- vino_launch/launch/pipeline_param.launch | 8 ++++++++ 1 file changed, 8 insertions(+) create mode 100644 vino_launch/launch/pipeline_param.launch diff --git a/vino_launch/launch/pipeline_param.launch b/vino_launch/launch/pipeline_param.launch new file mode 100644 index 00000000..49f04a1d --- /dev/null +++ b/vino_launch/launch/pipeline_param.launch @@ -0,0 +1,8 @@ + + + + + + + From f666aec19bc56de6c7b276bb8c02d86e02037624 Mon Sep 17 00:00:00 2001 From: luyang00 <393780933@qq.com> Date: Thu, 7 Mar 2019 14:52:15 +0800 Subject: [PATCH 03/15] add support for person re-id --- dynamic_vino_lib/CMakeLists.txt | 2 + .../inferences/person_reidentification.h | 122 ++++++++++++++ .../models/person_reidentification_model.h | 48 ++++++ .../dynamic_vino_lib/outputs/base_output.h | 7 + .../outputs/image_window_output.h | 11 +- .../dynamic_vino_lib/pipeline_manager.h | 2 + .../dynamic_vino_lib/pipeline_params.h | 1 + .../inferences/person_reidentification.cpp | 153 ++++++++++++++++++ .../models/person_reidentification_model.cpp | 50 ++++++ .../src/outputs/image_window_output.cpp | 26 +++ dynamic_vino_lib/src/pipeline_manager.cpp | 19 +++ .../param/pipeline_reidentification.yaml | 27 ++++ .../include/vino_param_lib/param_manager.h | 3 + vino_param_lib/src/param_manager.cpp | 19 ++- 14 files changed, 487 insertions(+), 3 deletions(-) create mode 100644 dynamic_vino_lib/include/dynamic_vino_lib/inferences/person_reidentification.h create mode 100644 dynamic_vino_lib/include/dynamic_vino_lib/models/person_reidentification_model.h create mode 100644 dynamic_vino_lib/src/inferences/person_reidentification.cpp create mode 100644 dynamic_vino_lib/src/models/person_reidentification_model.cpp create mode 100644 vino_launch/param/pipeline_reidentification.yaml diff --git a/dynamic_vino_lib/CMakeLists.txt b/dynamic_vino_lib/CMakeLists.txt index e1d04721..1d9b1969 100644 --- a/dynamic_vino_lib/CMakeLists.txt +++ b/dynamic_vino_lib/CMakeLists.txt @@ -145,6 +145,7 @@ add_library(${PROJECT_NAME} SHARED src/inferences/head_pose_detection.cpp src/inferences/object_detection.cpp src/inferences/object_segmentation.cpp + src/inferences/person_reidentification.cpp src/inputs/realsense_camera.cpp src/inputs/realsense_camera_topic.cpp src/inputs/standard_camera.cpp @@ -157,6 +158,7 @@ add_library(${PROJECT_NAME} SHARED src/models/head_pose_detection_model.cpp src/models/object_detection_model.cpp src/models/object_segmentation_model.cpp + src/models/person_reidentification_model.cpp src/outputs/image_window_output.cpp src/outputs/ros_topic_output.cpp src/outputs/rviz_output.cpp diff --git a/dynamic_vino_lib/include/dynamic_vino_lib/inferences/person_reidentification.h b/dynamic_vino_lib/include/dynamic_vino_lib/inferences/person_reidentification.h new file mode 100644 index 00000000..72b9b7a0 --- /dev/null +++ b/dynamic_vino_lib/include/dynamic_vino_lib/inferences/person_reidentification.h @@ -0,0 +1,122 @@ +// Copyright (c) 2018 Intel Corporation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/** + * @brief A header file with declaration for PersonReidentification Class + * @file person_reidentification.hpp + */ +#ifndef DYNAMIC_VINO_LIB__INFERENCES__PERSON_REIDENTIFICATION_HPP_ +#define DYNAMIC_VINO_LIB__INFERENCES__PERSON_REIDENTIFICATION_HPP_ +#include +#include +#include +#include "dynamic_vino_lib/models/person_reidentification_model.h" +#include "dynamic_vino_lib/engines/engine.h" +#include "dynamic_vino_lib/inferences/base_inference.h" +#include "inference_engine.hpp" +#include "opencv2/opencv.hpp" +// namespace +namespace dynamic_vino_lib +{ +/** + * @class PersonReidentificationResult + * @brief Class for storing and processing face detection result. + */ +class PersonReidentificationResult : public Result +{ +public: + friend class PersonReidentification; + explicit PersonReidentificationResult(const cv::Rect & location); + std::string getPersonID() const {return person_id_;} + +private: + std::string person_id_ = "No.#"; +}; +/** + * @class PersonReidentification + * @brief Class to load face detection model and perform face detection. + */ +class PersonReidentification : public BaseInference +{ +public: + using Result = dynamic_vino_lib::PersonReidentificationResult; + explicit PersonReidentification(double); + ~PersonReidentification() override; + /** + * @brief Load the face detection model. + */ + void loadNetwork(std::shared_ptr); + /** + * @brief Enqueue a frame to this class. + * The frame will be buffered but not infered yet. + * @param[in] frame The frame to be enqueued. + * @param[in] input_frame_loc The location of the enqueued frame with respect + * to the frame generated by the input device. + * @return Whether this operation is successful. + */ + bool enqueue(const cv::Mat &, const cv::Rect &) override; + /** + * @brief Start inference for all buffered frames. + * @return Whether this operation is successful. + */ + bool submitRequest() override; + /** + * @brief This function will fetch the results of the previous inference and + * stores the results in a result buffer array. All buffered frames will be + * cleared. + * @return Whether the Inference object fetches a result this time + */ + bool fetchResults() override; + /** + * @brief Get the length of the buffer result array. + * @return The length of the buffer result array. + */ + const int getResultsLength() const override; + /** + * @brief Get the location of result with respect + * to the frame generated by the input device. + * @param[in] idx The index of the result. + */ + const dynamic_vino_lib::Result * getLocationResult(int idx) const override; + /** + * @brief Show the observed detection result either through image window + or ROS topic. + */ + const void observeOutput(const std::shared_ptr & output); + /** + * @brief Get the name of the Inference instance. + * @return The name of the Inference instance. + */ + const std::string getName() const override; + /** + * @brief Calculate the similarity between a new detected person with + * the already recorded persons. + * @return The similarity value. + */ + float calcSimilarity(const std::vector &, const std::vector &); + /** + * @brief Try to find the matched person from the recorded persons, if there are not, + * record it in the recorded persons. + * @return The id of the matched person (or the new person). + */ + std::string findMatchPerson(const std::vector &); + +private: + std::shared_ptr valid_model_; + std::vector results_; + std::vector> recorded_persons_; + double match_thresh_ = 0; +}; +} // namespace dynamic_vino_lib +#endif // DYNAMIC_VINO_LIB__INFERENCES__PERSON_REIDENTIFICATION_HPP_ diff --git a/dynamic_vino_lib/include/dynamic_vino_lib/models/person_reidentification_model.h b/dynamic_vino_lib/include/dynamic_vino_lib/models/person_reidentification_model.h new file mode 100644 index 00000000..a9cff01f --- /dev/null +++ b/dynamic_vino_lib/include/dynamic_vino_lib/models/person_reidentification_model.h @@ -0,0 +1,48 @@ +// Copyright (c) 2018 Intel Corporation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/** + * @brief A header file with declaration for PersonReidentificationModel Class + * @file face_detection_model.h + */ +#ifndef DYNAMIC_VINO_LIB__MODELS__PERSON_REIDENTIFICATION_MODEL_HPP_ +#define DYNAMIC_VINO_LIB__MODELS__PERSON_REIDENTIFICATION_MODEL_HPP_ +#include +#include "dynamic_vino_lib/models/base_model.h" +namespace Models +{ +/** + * @class PersonReidentificationModel + * @brief This class generates the person reidentification model. + */ +class PersonReidentificationModel : public BaseModel +{ +public: + PersonReidentificationModel(const std::string &, int, int, int); + inline const std::string getInputName() {return input_;} + inline const std::string getOutputName() {return output_;} + /** + * @brief Get the name of this detection model. + * @return Name of the model. + */ + const std::string getModelName() const override; + +protected: + void checkLayerProperty(const InferenceEngine::CNNNetReader::Ptr &) override; + void setLayerProperty(InferenceEngine::CNNNetReader::Ptr) override; + std::string input_; + std::string output_; +}; +} // namespace Models +#endif // DYNAMIC_VINO_LIB__MODELS__PERSON_REIDENTIFICATION_MODEL_HPP_ diff --git a/dynamic_vino_lib/include/dynamic_vino_lib/outputs/base_output.h b/dynamic_vino_lib/include/dynamic_vino_lib/outputs/base_output.h index 50bd2dd9..f7eace98 100644 --- a/dynamic_vino_lib/include/dynamic_vino_lib/outputs/base_output.h +++ b/dynamic_vino_lib/include/dynamic_vino_lib/outputs/base_output.h @@ -32,6 +32,7 @@ #include "dynamic_vino_lib/inferences/head_pose_detection.h" #include "dynamic_vino_lib/inferences/object_detection.h" #include "dynamic_vino_lib/inferences/object_segmentation.h" +#include "dynamic_vino_lib/inferences/person_reidentification.h" #include "opencv2/opencv.hpp" class Pipeline; @@ -89,6 +90,12 @@ class BaseOutput virtual void accept(const std::vector&) { } + /** + * @brief Generate output content according to the person reidentification result. + */ + virtual void accept(const std::vector &) + { + } /** * @brief Calculate the camera matrix of a frame for image window output, no implementation for ros topic output. diff --git a/dynamic_vino_lib/include/dynamic_vino_lib/outputs/image_window_output.h b/dynamic_vino_lib/include/dynamic_vino_lib/outputs/image_window_output.h index 161a0c2b..2bdca7c2 100644 --- a/dynamic_vino_lib/include/dynamic_vino_lib/outputs/image_window_output.h +++ b/dynamic_vino_lib/include/dynamic_vino_lib/outputs/image_window_output.h @@ -89,14 +89,21 @@ class ImageWindowOutput : public BaseOutput * @param[in] An object segmentation result objetc. */ void accept(const std::vector&) override; - /** + /** + * @brief Generate image window output content according to + * the person re-ID result. + * @param[in] An object segmentation result objetc. + */ + void accept(const std::vector &) override; + /** * @brief Merge mask for image window ouput * the object segmentation result. * @param[in] An object segmentation result objetc. */ void mergeMask(const std::vector &); - private: + + unsigned findOutput(const cv::Rect &); void initOutputs(unsigned size); /** * @brief Calculate the axises of the coordinates for showing diff --git a/dynamic_vino_lib/include/dynamic_vino_lib/pipeline_manager.h b/dynamic_vino_lib/include/dynamic_vino_lib/pipeline_manager.h index 33af6678..7d4f5975 100644 --- a/dynamic_vino_lib/include/dynamic_vino_lib/pipeline_manager.h +++ b/dynamic_vino_lib/include/dynamic_vino_lib/pipeline_manager.h @@ -96,6 +96,8 @@ class PipelineManager { const Params::ParamManager::InferenceParams& infer); std::shared_ptr createObjectSegmentation( const Params::ParamManager::InferenceParams& infer); + std::shared_ptr createPersonReidentification( + const Params::ParamManager::InferenceParams& infer); std::map pipelines_; std::map plugins_for_devices_; }; diff --git a/dynamic_vino_lib/include/dynamic_vino_lib/pipeline_params.h b/dynamic_vino_lib/include/dynamic_vino_lib/pipeline_params.h index c6447ad9..ec9dc36f 100644 --- a/dynamic_vino_lib/include/dynamic_vino_lib/pipeline_params.h +++ b/dynamic_vino_lib/include/dynamic_vino_lib/pipeline_params.h @@ -54,6 +54,7 @@ const char kInferTpye_EmotionRecognition[] = "emotion_detection"; const char kInferTpye_HeadPoseEstimation[] = "head_pose_detection"; const char kInferTpye_ObjectDetection[] = "ObjectDetection"; const char kInferTpye_ObjectSegmentation[] = "ObjectSegmentation"; +const char kInferTpye_PersonReidentification[] = "PersonReidentification"; /** * @class PipelineParams diff --git a/dynamic_vino_lib/src/inferences/person_reidentification.cpp b/dynamic_vino_lib/src/inferences/person_reidentification.cpp new file mode 100644 index 00000000..005a128d --- /dev/null +++ b/dynamic_vino_lib/src/inferences/person_reidentification.cpp @@ -0,0 +1,153 @@ +// Copyright (c) 2018 Intel Corporation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/** + * @brief a header file with declaration of PersonReidentification class and + * PersonReidentificationResult class + * @file person_reidentification.cpp + */ +#include +#include +#include +#include "dynamic_vino_lib/inferences/person_reidentification.h" +#include "dynamic_vino_lib/outputs/base_output.h" +#include "dynamic_vino_lib/slog.h" + +// PersonReidentificationResult +dynamic_vino_lib::PersonReidentificationResult::PersonReidentificationResult( + const cv::Rect & location) +: Result(location) {} + +// PersonReidentification +dynamic_vino_lib::PersonReidentification::PersonReidentification(double match_thresh) +: match_thresh_(match_thresh), dynamic_vino_lib::BaseInference() {} + +dynamic_vino_lib::PersonReidentification::~PersonReidentification() = default; +void dynamic_vino_lib::PersonReidentification::loadNetwork( + const std::shared_ptr network) +{ + valid_model_ = network; + setMaxBatchSize(network->getMaxBatchSize()); +} + +bool dynamic_vino_lib::PersonReidentification::enqueue( + const cv::Mat & frame, const cv::Rect & input_frame_loc) +{ + if (getEnqueuedNum() == 0) { + results_.clear(); + } + if (!dynamic_vino_lib::BaseInference::enqueue( + frame, input_frame_loc, 1, 0, valid_model_->getInputName())) + { + return false; + } + Result r(input_frame_loc); + results_.emplace_back(r); + return true; +} + +bool dynamic_vino_lib::PersonReidentification::submitRequest() +{ + return dynamic_vino_lib::BaseInference::submitRequest(); +} + +bool dynamic_vino_lib::PersonReidentification::fetchResults() +{ + bool can_fetch = dynamic_vino_lib::BaseInference::fetchResults(); + if (!can_fetch) {return false;} + bool found_result = false; + InferenceEngine::InferRequest::Ptr request = getEngine()->getRequest(); + std::string output = valid_model_->getOutputName(); + const float * output_values = request->GetBlob(output)->buffer().as(); + for (int i = 0; i < getResultsLength(); i++) { + std::vector new_person = std::vector( + output_values + 256 * i, output_values + 256 * i + 256); + std::string person_id = findMatchPerson(new_person); + results_[i].person_id_ = person_id; + found_result = true; + } + if (!found_result) {results_.clear();} + return true; +} + +float dynamic_vino_lib::PersonReidentification::calcSimilarity( + const std::vector & person_a, const std::vector & person_b) +{ + if (person_a.size() != person_b.size()) { + throw std::logic_error("cosine similarity can't be called for vectors of different lengths: " + "person_a size = " + std::to_string(person_a.size()) + + "person_b size = " + std::to_string(person_b.size())); + } + float mul_sum, denom_a, denom_b, value_a, value_b; + mul_sum = denom_a = denom_b = value_a = value_b = 0; + for (auto i = 0; i < person_a.size(); i++) { + value_a = person_a[i]; + value_b = person_b[i]; + mul_sum += value_a * value_b; + denom_a += value_a * value_a; + denom_b += value_b * value_b; + } + if (denom_a == 0 || denom_b == 0) { + throw std::logic_error("cosine similarity is not defined whenever one or both " + "input vectors are zero-vectors."); + } + return mul_sum / (sqrt(denom_a) * sqrt(denom_b)); +} + +std::string dynamic_vino_lib::PersonReidentification::findMatchPerson( + const std::vector & new_person) +{ + auto size = recorded_persons_.size(); + std::string id = "No."; + float best_match_sim = 0; + int best_match_ind = -1; + for (auto i = 0; i < size; ++i) { + float cos_sim = calcSimilarity(new_person, recorded_persons_[i]); + if (cos_sim > best_match_sim) { + best_match_sim = cos_sim; + best_match_ind = i; + } + } + if (best_match_sim > match_thresh_) { + recorded_persons_[best_match_ind] = new_person; + return id + std::to_string(best_match_ind); + } else { + recorded_persons_.push_back(new_person); + return id + std::to_string(size); + } +} + +const int dynamic_vino_lib::PersonReidentification::getResultsLength() const +{ + return static_cast(results_.size()); +} + +const dynamic_vino_lib::Result * +dynamic_vino_lib::PersonReidentification::getLocationResult(int idx) const +{ + return &(results_[idx]); +} + +const std::string dynamic_vino_lib::PersonReidentification::getName() const +{ + return valid_model_->getModelName(); +} + +const void dynamic_vino_lib::PersonReidentification::observeOutput( + const std::shared_ptr & output) +{ + if (output != nullptr) { + output->accept(results_); + } +} diff --git a/dynamic_vino_lib/src/models/person_reidentification_model.cpp b/dynamic_vino_lib/src/models/person_reidentification_model.cpp new file mode 100644 index 00000000..7367e212 --- /dev/null +++ b/dynamic_vino_lib/src/models/person_reidentification_model.cpp @@ -0,0 +1,50 @@ +// Copyright (c) 2018 Intel Corporation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/** + * @brief a header file with declaration of PersonReidentificationModel class + * @file person_reidentification_model.cpp + */ +#include +#include "dynamic_vino_lib/models/person_reidentification_model.h" +#include "dynamic_vino_lib/slog.h" +// Validated Object Detection Network +Models::PersonReidentificationModel::PersonReidentificationModel( + const std::string & model_loc, int input_num, int output_num, int max_batch_size) +: BaseModel(model_loc, input_num, output_num, max_batch_size) {} + +void Models::PersonReidentificationModel::setLayerProperty( + InferenceEngine::CNNNetReader::Ptr net_reader) +{ + // set input property + InferenceEngine::InputsDataMap input_info_map( + net_reader->getNetwork().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()); + // set input and output layer name + input_ = input_info_map.begin()->first; + output_ = output_info_map.begin()->first; +} + +void Models::PersonReidentificationModel::checkLayerProperty( + const InferenceEngine::CNNNetReader::Ptr & net_reader) {} + +const std::string Models::PersonReidentificationModel::getModelName() const +{ + return "Person Reidentification"; +} diff --git a/dynamic_vino_lib/src/outputs/image_window_output.cpp b/dynamic_vino_lib/src/outputs/image_window_output.cpp index ee6d9fee..6e285f43 100644 --- a/dynamic_vino_lib/src/outputs/image_window_output.cpp +++ b/dynamic_vino_lib/src/outputs/image_window_output.cpp @@ -289,6 +289,32 @@ void Outputs::ImageWindowOutput::accept( mergeMask(results); } +unsigned Outputs::ImageWindowOutput::findOutput( + const cv::Rect & result_rect) +{ + for (unsigned i = 0; i < outputs_.size(); i++) { + if (outputs_[i].rect == result_rect) { + return i; + } + } + OutputData output; + output.desc = ""; + output.scalar = cv::Scalar(255, 0, 0); + outputs_.push_back(output); + return outputs_.size() - 1; +} + +void Outputs::ImageWindowOutput::accept( + const std::vector & results) +{ + for (unsigned i = 0; i < results.size(); i++) { + cv::Rect result_rect = results[i].getLocation(); + unsigned target_index = findOutput(result_rect); + outputs_[target_index].rect = result_rect; + outputs_[target_index].desc += "[" + results[i].getPersonID() + "]"; + } +} + void Outputs::ImageWindowOutput::decorateFrame() { if (getPipeline()->getParameters()->isGetFps()) diff --git a/dynamic_vino_lib/src/pipeline_manager.cpp b/dynamic_vino_lib/src/pipeline_manager.cpp index f7e4d989..d1056a06 100644 --- a/dynamic_vino_lib/src/pipeline_manager.cpp +++ b/dynamic_vino_lib/src/pipeline_manager.cpp @@ -193,6 +193,9 @@ PipelineManager::parseInference( else if (infer.name == kInferTpye_ObjectSegmentation) { object = createObjectSegmentation(infer); } + else if (infer.name == kInferTpye_PersonReidentification) { + object = createPersonReidentification(infer); + } else { slog::err << "Invalid inference name: " << infer.name << slog::endl; } @@ -301,6 +304,22 @@ PipelineManager::createObjectSegmentation(const Params::ParamManager::InferenceP return segmentation_inference_ptr; } +std::shared_ptr +PipelineManager::createPersonReidentification( + const Params::ParamManager::InferenceParams & infer) +{ + auto person_reidentification_model = + std::make_shared(infer.model, 1, 1, infer.batch); + person_reidentification_model->modelInit(); + auto person_reidentification_engine = std::make_shared( + plugins_for_devices_[infer.engine], person_reidentification_model); + auto reidentification_inference_ptr = + std::make_shared(infer.confidence_threshold); + reidentification_inference_ptr->loadNetwork(person_reidentification_model); + reidentification_inference_ptr->loadEngine(person_reidentification_engine); + + return reidentification_inference_ptr; +} void PipelineManager::threadPipeline(const char* name) { PipelineData& p = pipelines_[name]; diff --git a/vino_launch/param/pipeline_reidentification.yaml b/vino_launch/param/pipeline_reidentification.yaml new file mode 100644 index 00000000..e498bc9c --- /dev/null +++ b/vino_launch/param/pipeline_reidentification.yaml @@ -0,0 +1,27 @@ +Pipelines: +- name: object + inputs: [RealSenseCamera] + infers: + - name: ObjectDetection + model: /home/intel/code/open_model_zoo/model_downloader/Retail/object_detection/pedestrian/rmnet_ssd/0013/dldt/person-detection-retail-0013.xml + engine: CPU + label: to/be/set/xxx.labels + batch: 1 + confidence_threshold: 0.5 + enable_roi_constraint: true # set enable_roi_constraint to false if you don't want to make the inferred ROI (region of interest) constrained into the camera frame + - name: PersonReidentification + model: /home/intel/code/open_model_zoo/model_downloader/Retail/object_reidentification/pedestrian/rmnet_based/0076/dldt/person-reidentification-retail-0076.xml + engine: CPU + label: to/be/set/xxx.labels + batch: 1 + confidence_threshold: 0.7 + outputs: [ImageWindow, RViz, RosTopic] + connects: + - left: RealSenseCamera + right: [ObjectDetection] + - left: ObjectDetection + right: [PersonReidentification] + - left: PersonReidentification + right: [ImageWindow, RViz, RosTopic] + +OpenvinoCommon: \ No newline at end of file diff --git a/vino_param_lib/include/vino_param_lib/param_manager.h b/vino_param_lib/include/vino_param_lib/param_manager.h index 180bf26f..7166d933 100644 --- a/vino_param_lib/include/vino_param_lib/param_manager.h +++ b/vino_param_lib/include/vino_param_lib/param_manager.h @@ -69,6 +69,9 @@ class ParamManager // singleton std::string engine; std::string model; std::string label; + int batch; + float confidence_threshold = 0.5; + bool enable_roi_constraint = false; }; struct PipelineParams { diff --git a/vino_param_lib/src/param_manager.cpp b/vino_param_lib/src/param_manager.cpp index 6e907a30..3d5d2bb6 100644 --- a/vino_param_lib/src/param_manager.cpp +++ b/vino_param_lib/src/param_manager.cpp @@ -35,8 +35,9 @@ void operator>>(const YAML::Node& node, std::multimap& connect); void operator>>(const YAML::Node& node, std::string& str); void operator>>(const YAML::Node& node, bool& val); +void operator>>(const YAML::Node& node, int& val); +void operator>>(const YAML::Node& node, float& val); void operator>>(const YAML::Node& node, ParamManager::CommonParams& common); - #define YAML_PARSE(node, key, val) \ try \ { \ @@ -101,6 +102,9 @@ void operator>>(const YAML::Node& node, ParamManager::InferenceParams& infer) YAML_PARSE(node, "model", infer.model) YAML_PARSE(node, "engine", infer.engine) YAML_PARSE(node, "label", infer.label) + YAML_PARSE(node, "batch", infer.batch) + YAML_PARSE(node, "confidence_threshold", infer.confidence_threshold) + YAML_PARSE(node, "enable_roi_constraint", infer.enable_roi_constraint) slog::info << "Inference Params:name=" << infer.name << slog::endl; } @@ -140,6 +144,16 @@ void operator>>(const YAML::Node& node, bool& val) val = node.as(); } +void operator>>(const YAML::Node & node, int & val) +{ + val = node.as(); +} + +void operator>>(const YAML::Node & node, float & val) +{ + val = node.as(); +} + void ParamManager::print() const { slog::info << "--------parameters DUMP---------------------" << slog::endl; @@ -167,6 +181,9 @@ void ParamManager::print() const slog::info << "\t\tModel: " << infer.model << slog::endl; slog::info << "\t\tEngine: " << infer.engine << slog::endl; slog::info << "\t\tLabel: " << infer.label << slog::endl; + slog::info << "\t\tBatch: " << infer.batch << slog::endl; + slog::info << "\t\tConfidence_threshold: " << infer.confidence_threshold << slog::endl; + slog::info << "\t\tEnable_roi_constraint: " << infer.enable_roi_constraint << slog::endl; } slog::info << "\tConnections: " << slog::endl; From 4f810463e999ea3fd08181bfec8b209d13bcedcf Mon Sep 17 00:00:00 2001 From: luyang00 <393780933@qq.com> Date: Wed, 20 Mar 2019 11:46:39 +0800 Subject: [PATCH 04/15] add support for ROS service --- dynamic_vino_lib/CMakeLists.txt | 2 + .../dynamic_vino_lib/outputs/base_output.h | 14 +++ .../outputs/ros_service_output.h | 79 +++++++++++++ .../outputs/ros_topic_output.h | 6 +- .../include/dynamic_vino_lib/pipeline.h | 6 +- .../dynamic_vino_lib/pipeline_manager.h | 6 + .../services/frame_processing_server.h | 68 +++++++++++ .../src/outputs/ros_service_output.cpp | 104 +++++++++++++++++ dynamic_vino_lib/src/pipeline_manager.cpp | 5 +- .../src/services/frame_processing_server.cpp | 100 +++++++++++++++++ people_msgs/CMakeLists.txt | 8 ++ people_msgs/msg/PersonsStamped.msg | 19 ++++ people_msgs/srv/AgeGenderSrv.srv | 18 +++ people_msgs/srv/EmotionSrv.srv | 17 +++ people_msgs/srv/HeadPoseSrv.srv | 16 +++ people_msgs/srv/PeopleSrv.srv | 18 +++ sample/CMakeLists.txt | 78 +++++++++++++ sample/src/image_object_client.cpp | 102 +++++++++++++++++ sample/src/image_object_server.cpp | 102 +++++++++++++++++ sample/src/image_people_client.cpp | 76 +++++++++++++ sample/src/image_people_server.cpp | 106 ++++++++++++++++++ vino_launch/launch/image_object_server.launch | 14 +++ vino_launch/launch/image_people_server.launch | 14 +++ vino_launch/launch/pipeline_param.launch | 2 +- vino_launch/param/image_object_server.yaml | 18 +++ vino_launch/param/image_people_server.yaml | 39 +++++++ vino_launch/param/pipeline_object.yaml | 4 +- .../include/vino_param_lib/param_manager.h | 2 - 28 files changed, 1033 insertions(+), 10 deletions(-) create mode 100644 dynamic_vino_lib/include/dynamic_vino_lib/outputs/ros_service_output.h create mode 100644 dynamic_vino_lib/include/dynamic_vino_lib/services/frame_processing_server.h create mode 100644 dynamic_vino_lib/src/outputs/ros_service_output.cpp create mode 100644 dynamic_vino_lib/src/services/frame_processing_server.cpp create mode 100644 people_msgs/msg/PersonsStamped.msg create mode 100644 people_msgs/srv/AgeGenderSrv.srv create mode 100644 people_msgs/srv/EmotionSrv.srv create mode 100644 people_msgs/srv/HeadPoseSrv.srv create mode 100644 people_msgs/srv/PeopleSrv.srv create mode 100644 sample/src/image_object_client.cpp create mode 100644 sample/src/image_object_server.cpp create mode 100644 sample/src/image_people_client.cpp create mode 100644 sample/src/image_people_server.cpp create mode 100644 vino_launch/launch/image_object_server.launch create mode 100644 vino_launch/launch/image_people_server.launch create mode 100644 vino_launch/param/image_object_server.yaml create mode 100644 vino_launch/param/image_people_server.yaml diff --git a/dynamic_vino_lib/CMakeLists.txt b/dynamic_vino_lib/CMakeLists.txt index 1d9b1969..b9fae78d 100644 --- a/dynamic_vino_lib/CMakeLists.txt +++ b/dynamic_vino_lib/CMakeLists.txt @@ -133,6 +133,7 @@ endif() set(DEPENDENCIES realsense2 ${OpenCV_LIBS} cpu_extension) add_library(${PROJECT_NAME} SHARED + src/services/frame_processing_server.cpp src/factory.cpp src/pipeline.cpp src/pipeline_params.cpp @@ -163,6 +164,7 @@ add_library(${PROJECT_NAME} SHARED src/outputs/ros_topic_output.cpp src/outputs/rviz_output.cpp src/outputs/base_output.cpp + src/outputs/ros_service_output.cpp ) add_dependencies(${PROJECT_NAME} diff --git a/dynamic_vino_lib/include/dynamic_vino_lib/outputs/base_output.h b/dynamic_vino_lib/include/dynamic_vino_lib/outputs/base_output.h index f7eace98..50e66767 100644 --- a/dynamic_vino_lib/include/dynamic_vino_lib/outputs/base_output.h +++ b/dynamic_vino_lib/include/dynamic_vino_lib/outputs/base_output.h @@ -33,6 +33,7 @@ #include "dynamic_vino_lib/inferences/object_detection.h" #include "dynamic_vino_lib/inferences/object_segmentation.h" #include "dynamic_vino_lib/inferences/person_reidentification.h" +#include "dynamic_vino_lib/services/frame_processing_server.h" #include "opencv2/opencv.hpp" class Pipeline; @@ -113,8 +114,21 @@ class BaseOutput int getFPS() const; void setPipeline(Pipeline* const pipeline); + virtual void setServiceResponse( + boost::shared_ptr response) {} + virtual void setServiceResponseForFace( + boost::shared_ptr response) {} + virtual void setServiceResponse( + boost::shared_ptr response) {} + virtual void setServiceResponse( + boost::shared_ptr response) {} + virtual void setServiceResponse( + boost::shared_ptr response) {} + virtual void setServiceResponse( + boost::shared_ptr response) {} Pipeline* getPipeline() const; cv::Mat getFrame() const; + virtual void clearData() {} protected: cv::Mat frame_; diff --git a/dynamic_vino_lib/include/dynamic_vino_lib/outputs/ros_service_output.h b/dynamic_vino_lib/include/dynamic_vino_lib/outputs/ros_service_output.h new file mode 100644 index 00000000..c0cffb74 --- /dev/null +++ b/dynamic_vino_lib/include/dynamic_vino_lib/outputs/ros_service_output.h @@ -0,0 +1,79 @@ +// Copyright (c) 2018 Intel Corporation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/** + * @brief A header file with declaration for RosTopicOutput Class + * @file ros_topic_output.h + */ + +#ifndef DYNAMIC_VINO_LIB__OUTPUTS__ROS_SERVICE_OUTPUT_HPP_ +#define DYNAMIC_VINO_LIB__OUTPUTS__ROS_SERVICE_OUTPUT_HPP_ + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include + + + +#include + +#include +#include +#include + +#include "dynamic_vino_lib/inferences/face_detection.h" +#include "dynamic_vino_lib/outputs/ros_topic_output.h" + +namespace Outputs +{ +/** + * @class RosServiceOutput + * @brief This class handles and publish the detection result for service calling. + */ +class RosServiceOutput : public RosTopicOutput +{ +public: + RosServiceOutput() {} + + /** + * @brief Publish all the detected infomations generated by the accept + * functions with ros topic. + */ + void handleOutput() override {} + void clearData(); + + void setServiceResponse(boost::shared_ptr response); + void setResponseForFace(boost::shared_ptr response); + void setServiceResponse(boost::shared_ptr response); + void setServiceResponse(boost::shared_ptr response); + void setServiceResponse(boost::shared_ptr response); + void setServiceResponse(boost::shared_ptr response); + +private: + const std::string service_name_; +}; +} // namespace Outputs +#endif // DYNAMIC_VINO_LIB__OUTPUTS__ROS_SERVICE_OUTPUT_HPP_ diff --git a/dynamic_vino_lib/include/dynamic_vino_lib/outputs/ros_topic_output.h b/dynamic_vino_lib/include/dynamic_vino_lib/outputs/ros_topic_output.h index 96da76f1..0486df9c 100644 --- a/dynamic_vino_lib/include/dynamic_vino_lib/outputs/ros_topic_output.h +++ b/dynamic_vino_lib/include/dynamic_vino_lib/outputs/ros_topic_output.h @@ -79,8 +79,8 @@ class RosTopicOutput : public BaseOutput * the age gender detection result. * @param[in] An age gender detection result objetc. */ - void accept(const std::vector&) override; - /** + void accept(const std::vector &) override; + /**detected_objects_topic_ * @brief Generate ros topic infomation according to * the headpose detection result. * @param[in] An head pose detection result objetc. @@ -99,7 +99,7 @@ class RosTopicOutput : public BaseOutput const std::string topic_name_; cv::Mat frame_; ros::NodeHandle nh_; - + protected: ros::Publisher pub_face_; std::shared_ptr faces_msg_ptr_; ros::Publisher pub_emotion_; diff --git a/dynamic_vino_lib/include/dynamic_vino_lib/pipeline.h b/dynamic_vino_lib/include/dynamic_vino_lib/pipeline.h index 49360cf4..91ec6457 100644 --- a/dynamic_vino_lib/include/dynamic_vino_lib/pipeline.h +++ b/dynamic_vino_lib/include/dynamic_vino_lib/pipeline.h @@ -126,7 +126,11 @@ class Pipeline { return input_device_; } - + std::map> getOutputHandle() + { + return name_to_output_map_; + } + private: void initInferenceCounter(); void increaseInferenceCounter(); diff --git a/dynamic_vino_lib/include/dynamic_vino_lib/pipeline_manager.h b/dynamic_vino_lib/include/dynamic_vino_lib/pipeline_manager.h index 7d4f5975..3deb2aa9 100644 --- a/dynamic_vino_lib/include/dynamic_vino_lib/pipeline_manager.h +++ b/dynamic_vino_lib/include/dynamic_vino_lib/pipeline_manager.h @@ -72,6 +72,12 @@ class PipelineManager { std::shared_ptr thread; PipelineState state; }; + + std::map getPipelines() + { + return pipelines_; + } + private: PipelineManager(){}; diff --git a/dynamic_vino_lib/include/dynamic_vino_lib/services/frame_processing_server.h b/dynamic_vino_lib/include/dynamic_vino_lib/services/frame_processing_server.h new file mode 100644 index 00000000..562a41bd --- /dev/null +++ b/dynamic_vino_lib/include/dynamic_vino_lib/services/frame_processing_server.h @@ -0,0 +1,68 @@ +// Copyright (c) 2018 Intel Corporation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +#ifndef DYNAMIC_VINO_LIB__SERVICES__FRAME_PROCESSING_SERVER_HPP_ +#define DYNAMIC_VINO_LIB__SERVICES__FRAME_PROCESSING_SERVER_HPP_ + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +#include +#include +#include +#include + +namespace vino_service +{ +template +class FrameProcessingServer //: public ros::NodeHandle +{ +public: + explicit FrameProcessingServer( + const std::string & service_name, + const std::string & config_path); + void initService(const std::string & config_path); + +//private: + std::shared_ptr nh_; + +/* + void cbService( + std::shared_ptr request, + std::shared_ptr response); +*/ + bool cbService(ros::ServiceEvent& event); + // rclcpp::Service::SharedPtr service_; + //ros::NodeHandle nh_; + std::shared_ptr service_; + ros::ServiceServer srv; + std::string service_name_; + std::string config_path_; + + bool add3(ros::ServiceEvent &); +}; +} // namespace vino_service +#endif // DYNAMIC_VINO_LIB__SERVICES__FRAME_PROCESSING_SERVER_HPP_ \ No newline at end of file diff --git a/dynamic_vino_lib/src/outputs/ros_service_output.cpp b/dynamic_vino_lib/src/outputs/ros_service_output.cpp new file mode 100644 index 00000000..4bed2cfc --- /dev/null +++ b/dynamic_vino_lib/src/outputs/ros_service_output.cpp @@ -0,0 +1,104 @@ +// Copyright (c) 2018 Intel Corporation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/** + * @brief a header file with declaration of RosServiceOutput class + * @file ros_service_output.cpp + */ + +#include +#include +#include +#include "dynamic_vino_lib/outputs/ros_service_output.h" +#include "cv_bridge/cv_bridge.h" + +// Outputs::RosServiceOutput::RosServiceOutput() + + +void Outputs::RosServiceOutput::setServiceResponse( + boost::shared_ptr response) +{ + if (object_msg_ptr_ != nullptr && object_msg_ptr_->objects_vector.size() > 0) { + response->objects.objects_vector = object_msg_ptr_->objects_vector; + } else if (faces_msg_ptr_ != nullptr && faces_msg_ptr_ ->objects_vector.size() > 0) { + response->objects.objects_vector = faces_msg_ptr_->objects_vector; + } +} + +void Outputs::RosServiceOutput::setResponseForFace( + boost::shared_ptr response) +{ + if (faces_msg_ptr_ != nullptr && faces_msg_ptr_->objects_vector.size() > 0) { + response->objects.objects_vector = faces_msg_ptr_->objects_vector; + } +} + +void Outputs::RosServiceOutput::setServiceResponse( + boost::shared_ptr response) +{ + if (age_gender_msg_ptr_ != nullptr) { + response->age_gender.objects = age_gender_msg_ptr_->objects; + } +} + +void Outputs::RosServiceOutput::setServiceResponse( + boost::shared_ptr response) +{ + if (emotions_msg_ptr_ != nullptr) { + response->emotion.emotions = emotions_msg_ptr_->emotions; + } +} + +void Outputs::RosServiceOutput::setServiceResponse( + boost::shared_ptr response) +{ + if (headpose_msg_ptr_ != nullptr) { + response->headpose.headposes = headpose_msg_ptr_->headposes; + } +} + +void Outputs::RosServiceOutput::setServiceResponse( + boost::shared_ptr response) +{ + slog::info << "in People::Response ..."; + if (faces_msg_ptr_ != nullptr) { + slog::info << "[FACES],"; + response->persons.faces = faces_msg_ptr_->objects_vector; + } else if (object_msg_ptr_ != nullptr) { + slog::info << "[FACES(objects)],"; + response->persons.faces = object_msg_ptr_->objects_vector; + } + if (age_gender_msg_ptr_ != nullptr) { + slog::info << "[AGE_GENDER],"; + response->persons.agegenders = age_gender_msg_ptr_->objects; + } + if (emotions_msg_ptr_ != nullptr) { + slog::info << "[EMOTION],"; + response->persons.emotions = emotions_msg_ptr_->emotions; + } + if (headpose_msg_ptr_ != nullptr) { + slog::info << "[HEADPOSE],"; + response->persons.headposes = headpose_msg_ptr_->headposes; + } + slog::info << "DONE!" << slog::endl; +} + +void Outputs::RosServiceOutput::clearData() +{ + faces_msg_ptr_ = nullptr; + object_msg_ptr_ = nullptr; + age_gender_msg_ptr_ = nullptr; + emotions_msg_ptr_ = nullptr; + headpose_msg_ptr_ = nullptr; +} diff --git a/dynamic_vino_lib/src/pipeline_manager.cpp b/dynamic_vino_lib/src/pipeline_manager.cpp index d1056a06..42e173bd 100644 --- a/dynamic_vino_lib/src/pipeline_manager.cpp +++ b/dynamic_vino_lib/src/pipeline_manager.cpp @@ -41,6 +41,7 @@ #include "dynamic_vino_lib/outputs/image_window_output.h" #include "dynamic_vino_lib/outputs/ros_topic_output.h" #include "dynamic_vino_lib/outputs/rviz_output.h" +#include "dynamic_vino_lib/outputs/ros_service_output.h" #include "dynamic_vino_lib/pipeline.h" #include "dynamic_vino_lib/pipeline_manager.h" #include "dynamic_vino_lib/pipeline_params.h" @@ -142,7 +143,9 @@ PipelineManager::parseOutput( object = std::make_shared("Results"); } else if (name == kOutputTpye_RViz) { object = std::make_shared(); - } + } else if (name == kOutputTpye_RosService) { + object = std::make_shared(); + } if (object != nullptr) { outputs.insert({name, object}); slog::info << " ... Adding one Output: " << name << slog::endl; diff --git a/dynamic_vino_lib/src/services/frame_processing_server.cpp b/dynamic_vino_lib/src/services/frame_processing_server.cpp new file mode 100644 index 00000000..c4075da2 --- /dev/null +++ b/dynamic_vino_lib/src/services/frame_processing_server.cpp @@ -0,0 +1,100 @@ +// Copyright (c) 2018 Intel Corporation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "dynamic_vino_lib/services/frame_processing_server.h" +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "dynamic_vino_lib/pipeline_manager.h" +#include "dynamic_vino_lib/pipeline.h" +#include "dynamic_vino_lib/inputs/base_input.h" +#include "dynamic_vino_lib/inputs/image_input.h" +#include "dynamic_vino_lib/slog.h" + +namespace vino_service +{ +template +FrameProcessingServer::FrameProcessingServer( + const std::string & service_name, + const std::string & config_path): + service_name_(service_name), + config_path_(config_path) +{ + nh_=std::make_shared(); + initService(config_path); +} + +template +void FrameProcessingServer::initService( + const std::string & config_path) +{ + Params::ParamManager::getInstance().parse(config_path); + Params::ParamManager::getInstance().print(); + auto pcommon = Params::ParamManager::getInstance().getCommon(); + auto pipelines = Params::ParamManager::getInstance().getPipelines(); + + if (pipelines.size() != 1) { + throw std::logic_error("1 and only 1 pipeline can be set to FrameProcessServer!"); + } + + for (auto & p : pipelines) { + PipelineManager::getInstance().createPipeline(p); + } + + ros::ServiceServer srv = nh_->advertiseService >("/openvino_toolkit/service",std::bind(&FrameProcessingServer::cbService,this,std::placeholders::_1)); + service_ = std::make_shared(srv); +} + + + +template +bool FrameProcessingServer::cbService( + ros::ServiceEvent& event) +{ + boost::shared_ptr res = boost::make_shared(); + std::map pipelines_ = + PipelineManager::getInstance().getPipelines(); + for (auto it = pipelines_.begin(); it != pipelines_.end(); ++it) { + PipelineManager::PipelineData & p = pipelines_[it->second.params.name.c_str()]; + auto input = p.pipeline->getInputDevice(); + + p.pipeline->runOnce(); + auto output_handle = p.pipeline->getOutputHandle(); + + for (auto & pair : output_handle) { + if (!pair.first.compare(kOutputTpye_RosService)) { + pair.second->setServiceResponse(res); + //Ugly implement because of type difine + event.getResponse() = *res; + pair.second->clearData(); + return true; // TODO(weizhi) , return directly, suppose only 1 pipeline dealing with 1 request. + } + } + } + slog::info << "[FrameProcessingServer] Callback finished!" << slog::endl; + +} + + + +template class FrameProcessingServer; +template class FrameProcessingServer; +} // namespace vino_service diff --git a/people_msgs/CMakeLists.txt b/people_msgs/CMakeLists.txt index 41575182..a2c13e68 100644 --- a/people_msgs/CMakeLists.txt +++ b/people_msgs/CMakeLists.txt @@ -30,12 +30,20 @@ add_message_files(DIRECTORY msg FILES EmotionsStamped.msg HeadPose.msg HeadPoseStamped.msg + PersonsStamped.msg ) +add_service_files(FILES + AgeGenderSrv.srv + EmotionSrv.srv + HeadPoseSrv.srv + PeopleSrv.srv +) generate_messages(DEPENDENCIES std_msgs sensor_msgs geometry_msgs + object_msgs ) catkin_package( diff --git a/people_msgs/msg/PersonsStamped.msg b/people_msgs/msg/PersonsStamped.msg new file mode 100644 index 00000000..2aae1a08 --- /dev/null +++ b/people_msgs/msg/PersonsStamped.msg @@ -0,0 +1,19 @@ +# Copyright (c) 2018 Intel Corporation +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +std_msgs/Header header +object_msgs/ObjectInBox[] faces +people_msgs/Emotion[] emotions +people_msgs/AgeGender[] agegenders +people_msgs/HeadPose[] headposes diff --git a/people_msgs/srv/AgeGenderSrv.srv b/people_msgs/srv/AgeGenderSrv.srv new file mode 100644 index 00000000..9e2ab5d4 --- /dev/null +++ b/people_msgs/srv/AgeGenderSrv.srv @@ -0,0 +1,18 @@ +# Copyright (c) 2018 Intel Corporation +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +string image_path # input: an image +--- +AgeGenderStamped age_gender # output: age and gender result + diff --git a/people_msgs/srv/EmotionSrv.srv b/people_msgs/srv/EmotionSrv.srv new file mode 100644 index 00000000..836fbc38 --- /dev/null +++ b/people_msgs/srv/EmotionSrv.srv @@ -0,0 +1,17 @@ +# Copyright (c) 2018 Intel Corporation +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +string image_path # input: an image +--- +EmotionsStamped emotion # output: emotion result diff --git a/people_msgs/srv/HeadPoseSrv.srv b/people_msgs/srv/HeadPoseSrv.srv new file mode 100644 index 00000000..96fcbc43 --- /dev/null +++ b/people_msgs/srv/HeadPoseSrv.srv @@ -0,0 +1,16 @@ +## Copyright (c) 2018 Intel Corporation +## Licensed under the Apache License, Version 2.0 (the "License"); +## you may not use this file except in compliance with the License. +## You may obtain a copy of the License at +## +## http://www.apache.org/licenses/LICENSE-2.0 +## +## Unless required by applicable law or agreed to in writing, software +## distributed under the License is distributed on an "AS IS" BASIS, +## WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +## See the License for the specific language governing permissions and +## limitations under the License. + +string image_path # input: an image +--- +HeadPoseStamped headpose # output: headpose result diff --git a/people_msgs/srv/PeopleSrv.srv b/people_msgs/srv/PeopleSrv.srv new file mode 100644 index 00000000..4ac8b173 --- /dev/null +++ b/people_msgs/srv/PeopleSrv.srv @@ -0,0 +1,18 @@ +# Copyright (c) 2018 Intel Corporation +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +string image_path # input: an image +--- +PersonsStamped persons # output: emotion result + diff --git a/sample/CMakeLists.txt b/sample/CMakeLists.txt index b696ba3a..f59593b9 100644 --- a/sample/CMakeLists.txt +++ b/sample/CMakeLists.txt @@ -154,6 +154,84 @@ target_link_libraries(pipeline_with_params ${OpenCV_LIBRARIES} ) +add_executable(image_people_server + src/image_people_server.cpp +) + +add_dependencies(image_people_server + ${${PROJECT_NAME}_EXPORTED_TARGETS} + ${catkin_EXPORTED_TARGETS} + ${dynamic_vino_lib_TARGETS} +) + +target_link_libraries(image_people_server + ${catkin_LIBRARIES} + cpu_extension + gflags + ${vino_param_lib_LIBRARIES} + ${InferenceEngine_LIBRARIES} + ${OpenCV_LIBRARIES} +) + + +add_executable(image_people_client + src/image_people_client.cpp +) + +add_dependencies(image_people_client + ${${PROJECT_NAME}_EXPORTED_TARGETS} + ${catkin_EXPORTED_TARGETS} + ${dynamic_vino_lib_TARGETS} +) + +target_link_libraries(image_people_client + ${catkin_LIBRARIES} + cpu_extension + gflags + ${vino_param_lib_LIBRARIES} + ${InferenceEngine_LIBRARIES} + ${OpenCV_LIBRARIES} +) + +add_executable(image_object_server + src/image_object_server.cpp +) + +add_dependencies(image_object_server + ${${PROJECT_NAME}_EXPORTED_TARGETS} + ${catkin_EXPORTED_TARGETS} + ${dynamic_vino_lib_TARGETS} +) + +target_link_libraries(image_object_server + ${catkin_LIBRARIES} + cpu_extension + gflags + ${vino_param_lib_LIBRARIES} + ${InferenceEngine_LIBRARIES} + ${OpenCV_LIBRARIES} +) + + +add_executable(image_object_client + src/image_object_client.cpp +) + +add_dependencies(image_object_client + ${${PROJECT_NAME}_EXPORTED_TARGETS} + ${catkin_EXPORTED_TARGETS} + ${dynamic_vino_lib_TARGETS} +) + +target_link_libraries(image_object_client + ${catkin_LIBRARIES} + cpu_extension + gflags + ${vino_param_lib_LIBRARIES} + ${InferenceEngine_LIBRARIES} + ${OpenCV_LIBRARIES} +) + if(UNIX OR APPLE) # Linker flags. if( ${CMAKE_CXX_COMPILER_ID} STREQUAL "GNU" OR ${CMAKE_CXX_COMPILER_ID} STREQUAL "Intel") diff --git a/sample/src/image_object_client.cpp b/sample/src/image_object_client.cpp new file mode 100644 index 00000000..b8bae4bb --- /dev/null +++ b/sample/src/image_object_client.cpp @@ -0,0 +1,102 @@ +/* + * Copyright (c) 2018 Intel Corporation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** +* \brief A sample for this library. This sample performs face detection, + * emotions detection, age gender detection and head pose estimation. +* \file sample/main.cpp +*/ + +#include +#include +#include "opencv2/opencv.hpp" + +#include + + + + +int main(int argc, char ** argv) +{ + ros::init(argc, argv, "image_object_client"); + + ros::NodeHandle n; + + if (argc != 2) { + ROS_INFO("Usage: rosrun dynamic_vino_sample image_object_client "); + //You can find a sample image in /opt/openvino_toolkit/ros_openvino_toolkit/data/images/car.png + return -1; + } + + std::string image_path = argv[1]; + ros::ServiceClient client = n.serviceClient("/openvino_toolkit/service"); + + + object_msgs::DetectObject srv; + + if (client.call(srv)) + { + ROS_INFO("Request service success!"); + + cv::Mat image = cv::imread(image_path); + int width = image.cols; + int height = image.rows; + + for (unsigned int i = 0; i < srv.response.objects.objects_vector.size(); i++) { + std::stringstream ss; + ss << srv.response.objects.objects_vector[i].object.object_name << ": " << + srv.response.objects.objects_vector[i].object.probability * 100 << "%"; + ROS_INFO("%d: object: %s", i, + srv.response.objects.objects_vector[i].object.object_name.c_str()); + ROS_INFO( "prob: %f", + srv.response.objects.objects_vector[i].object.probability); + ROS_INFO( + "location: (%d, %d, %d, %d)", + srv.response.objects.objects_vector[i].roi.x_offset, srv.response.objects.objects_vector[i].roi.y_offset, + srv.response.objects.objects_vector[i].roi.width, srv.response.objects.objects_vector[i].roi.height); + + int xmin = srv.response.objects.objects_vector[i].roi.x_offset; + int ymin = srv.response.objects.objects_vector[i].roi.y_offset; + int w = srv.response.objects.objects_vector[i].roi.width; + int h = srv.response.objects.objects_vector[i].roi.height; + + int xmax = ((xmin + w) < width) ? (xmin + w) : width; + int ymax = ((ymin + h) < height) ? (ymin + h) : height; + + cv::Point left_top = cv::Point(xmin, ymin); + cv::Point right_bottom = cv::Point(xmax, ymax); + cv::rectangle(image, left_top, right_bottom, cv::Scalar(0, 255, 0), 1, 8, 0); + cv::rectangle(image, cvPoint(xmin, ymin), cvPoint(xmax, ymin + 20), cv::Scalar(0, 255, 0), + -1); + cv::putText(image, ss.str(), cvPoint(xmin + 5, ymin + 20), cv::FONT_HERSHEY_PLAIN, 1, + cv::Scalar(0, 0, 255), 1); + } + cv::imshow("image_detection", image); + cv::waitKey(0); + + + } else + { + ROS_ERROR("Failed to request service \"openvino_toolkit/service\" "); return -1; + } + + + + +} + + + \ No newline at end of file diff --git a/sample/src/image_object_server.cpp b/sample/src/image_object_server.cpp new file mode 100644 index 00000000..51754dec --- /dev/null +++ b/sample/src/image_object_server.cpp @@ -0,0 +1,102 @@ +/* + * Copyright (c) 2018 Intel Corporation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** +* \brief A sample for this library. This sample performs face detection, + * emotions detection, age gender detection and head pose estimation. +* \file sample/main.cpp +*/ + +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include "dynamic_vino_lib/common.h" +#include "dynamic_vino_lib/engines/engine.h" +#include "dynamic_vino_lib/factory.h" +#include "dynamic_vino_lib/inferences/age_gender_detection.h" +#include "dynamic_vino_lib/inferences/base_inference.h" +#include "dynamic_vino_lib/inferences/emotions_detection.h" +#include "dynamic_vino_lib/inferences/face_detection.h" +#include "dynamic_vino_lib/inferences/head_pose_detection.h" +#include "dynamic_vino_lib/inputs/realsense_camera_topic.h" +#include "dynamic_vino_lib/outputs/image_window_output.h" +#include "dynamic_vino_lib/outputs/ros_topic_output.h" +#include "dynamic_vino_lib/outputs/rviz_output.h" +#include "dynamic_vino_lib/pipeline.h" +#include "dynamic_vino_lib/pipeline_manager.h" +#include "dynamic_vino_lib/slog.h" +#include "inference_engine.hpp" +#include "opencv2/opencv.hpp" +#include "sample/utility.hpp" + +bool parseAndCheckCommandLine(int argc, char** argv) +{ + // -----Parsing and validation of input args--------------------------- + gflags::ParseCommandLineNonHelpFlags(&argc, &argv, true); + if (FLAGS_h) + { + showUsageForParam(); + return false; + } + + return true; +} + +int main(int argc, char** argv) +{ + ros::init(argc, argv, "image_object_servier"); + + if (!parseAndCheckCommandLine(argc, argv)) return 0; + + std::string param_path = ""; + ros::param::param("~param_file", param_path, "/param/pipeline_people.yaml"); + std::cout< +#include + +#include + + + +int main(int argc, char ** argv) +{ + ros::init(argc, argv, "image_people_client"); + ros::NodeHandle n; + + ros::ServiceClient client = n.serviceClient("/openvino_toolkit/service"); + + people_msgs::PeopleSrv srv; + + if (client.call(srv)) + { + ROS_INFO("Request service success!"); + + if (srv.response.persons.emotions.size() == 0 && srv.response.persons.agegenders.size() == 0 && + srv.response.persons.headposes.size() == 0) + { + ROS_INFO( "Get response, but no any person found."); + return 0; + } + ROS_INFO( "Found persons..."); + + for (unsigned int i = 0; i < srv.response.persons.faces.size(); i++) { + ROS_INFO( "%d: object: %s", i, + srv.response.persons.faces[i].object.object_name.c_str()); + ROS_INFO( "prob: %f", + srv.response.persons.faces[i].object.probability); + ROS_INFO( "location: (%d, %d, %d, %d)", + srv.response.persons.faces[i].roi.x_offset, srv.response.persons.faces[i].roi.y_offset, + srv.response.persons.faces[i].roi.width, srv.response.persons.faces[i].roi.height); + ROS_INFO( "Emotions: %s", + srv.response.persons.emotions[i].emotion.c_str()); + ROS_INFO( "Age: %f, Gender: %s", + srv.response.persons.agegenders[i].age, srv.response.persons.agegenders[i].gender.c_str()); + ROS_INFO( "Yaw, Pitch and Roll for head pose is: (%f, %f, %f),", + srv.response.persons.headposes[i].yaw, srv.response.persons.headposes[i].pitch, + srv.response.persons.headposes[i].roll); + } + } + else + { + ROS_ERROR("Failed to request service \"/openvino_toolkit/service\" "); + return -1; + } +} + + + \ No newline at end of file diff --git a/sample/src/image_people_server.cpp b/sample/src/image_people_server.cpp new file mode 100644 index 00000000..7e7bd95b --- /dev/null +++ b/sample/src/image_people_server.cpp @@ -0,0 +1,106 @@ +/* + * Copyright (c) 2018 Intel Corporation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** +* \brief A sample for this library. This sample performs face detection, + * emotions detection, age gender detection and head pose estimation. +* \file sample/main.cpp +*/ + +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include "dynamic_vino_lib/common.h" +#include "dynamic_vino_lib/engines/engine.h" +#include "dynamic_vino_lib/factory.h" +#include "dynamic_vino_lib/inferences/age_gender_detection.h" +#include "dynamic_vino_lib/inferences/base_inference.h" +#include "dynamic_vino_lib/inferences/emotions_detection.h" +#include "dynamic_vino_lib/inferences/face_detection.h" +#include "dynamic_vino_lib/inferences/head_pose_detection.h" +#include "dynamic_vino_lib/inputs/realsense_camera_topic.h" +#include "dynamic_vino_lib/outputs/image_window_output.h" +#include "dynamic_vino_lib/outputs/ros_topic_output.h" +#include "dynamic_vino_lib/outputs/rviz_output.h" +#include "dynamic_vino_lib/pipeline.h" +#include "dynamic_vino_lib/pipeline_manager.h" +#include "dynamic_vino_lib/slog.h" +#include "inference_engine.hpp" +#include "opencv2/opencv.hpp" +#include "sample/utility.hpp" + + +bool parseAndCheckCommandLine(int argc, char** argv) +{ + // -----Parsing and validation of input args--------------------------- + gflags::ParseCommandLineNonHelpFlags(&argc, &argv, true); + if (FLAGS_h) + { + showUsageForParam(); + return false; + } + + return true; +} + +int main(int argc, char** argv) +{ + ros::init(argc, argv, "sample_image_people_client"); + + if (!parseAndCheckCommandLine(argc, argv)) return 0; + + + std::string param_path = ""; + ros::param::param("~param_file", param_path, "/param/pipeline_people.yaml"); + + std::string prefix_path; + prefix_path = ros::package::getPath("vino_launch"); + + FLAGS_config = prefix_path + param_path; + + slog::info << "FLAGS_config=" << FLAGS_config << slog::endl; + + std::string service_name = "/openvino_toolkit/service"; + + slog::info << "service name=" << service_name << slog::endl; + + auto node = std::make_shared>(service_name, FLAGS_config); + + slog::info << "Waiting for service request..." << slog::endl; + + ros::spin(); + + slog::info << "--------------End of Excution--------------" << FLAGS_config << slog::endl; + +} diff --git a/vino_launch/launch/image_object_server.launch b/vino_launch/launch/image_object_server.launch new file mode 100644 index 00000000..7370f269 --- /dev/null +++ b/vino_launch/launch/image_object_server.launch @@ -0,0 +1,14 @@ + + + + + + + + diff --git a/vino_launch/launch/image_people_server.launch b/vino_launch/launch/image_people_server.launch new file mode 100644 index 00000000..33d8d846 --- /dev/null +++ b/vino_launch/launch/image_people_server.launch @@ -0,0 +1,14 @@ + + + + + + + + diff --git a/vino_launch/launch/pipeline_param.launch b/vino_launch/launch/pipeline_param.launch index 49f04a1d..0f54f6fc 100644 --- a/vino_launch/launch/pipeline_param.launch +++ b/vino_launch/launch/pipeline_param.launch @@ -1,5 +1,5 @@ - + diff --git a/vino_launch/param/image_object_server.yaml b/vino_launch/param/image_object_server.yaml new file mode 100644 index 00000000..9c096e84 --- /dev/null +++ b/vino_launch/param/image_object_server.yaml @@ -0,0 +1,18 @@ +Pipelines: +- name: object + inputs: [Image] + infers: + - name: ObjectDetection + model: /opt/openvino_toolkit/open_model_zoo/model_downloader/object_detection/common/ssd/300/caffe/output/ssd300.xml + engine: CPU + label: to/be/set/xxx.labels + batch: 16 + outputs: [RosService] + confidence_threshold: 0.2 + connects: + - left: Image + right: [ObjectDetection] + - left: ObjectDetection + right: [RosService] + input_path: "/opt/openvino_toolkit/ros_openvino_toolkit/data/images/car.png" +OpenvinoCommon: diff --git a/vino_launch/param/image_people_server.yaml b/vino_launch/param/image_people_server.yaml new file mode 100644 index 00000000..15380f3a --- /dev/null +++ b/vino_launch/param/image_people_server.yaml @@ -0,0 +1,39 @@ +Pipelines: +- name: people + inputs: [StandardCamera] + infers: + - name: face_detection + model: /home/intel/code/open_model_zoo/model_downloader/Transportation/object_detection/face/pruned_mobilenet_reduced_ssd_shared_weights/dldt/face-detection-adas-0001.xml + engine: CPU + label: to/be/set/xxx.labels + batch: 1 + - name: age_gender_detection + model: /home/intel/code/open_model_zoo/model_downloader/Retail/object_attributes/age_gender/dldt/age-gender-recognition-retail-0013.xml + engine: CPU + label: to/be/set/xxx.labels + batch: 16 + - name: emotion_detection + model: /home/intel/code/open_model_zoo/model_downloader/Retail/object_attributes/emotions_recognition/0003/dldt/emotions-recognition-retail-0003.xml + engine: CPU + label: to/be/set/xxx.labels + batch: 16 + - name: head_pose_detection + model: /home/intel/code/open_model_zoo/model_downloader/Transportation/object_attributes/headpose/vanilla_cnn/dldt/head-pose-estimation-adas-0001.xml + engine: CPU + label: to/be/set/xxx.labels + batch: 16 + outputs: [RosService] + confidence_threshold: 0.2 + connects: + - left: StandardCamera + right: [face_detection] + - left: face_detection + right: [age_gender_detection, emotion_detection, head_pose_detection, RosService] + - left: age_gender_detection + right: [RosService] + - left: emotion_detection + right: [RosService] + - left: head_pose_detection + right: [RosService] + +OpenvinoCommon: diff --git a/vino_launch/param/pipeline_object.yaml b/vino_launch/param/pipeline_object.yaml index 0ff3f993..08bf2ad5 100644 --- a/vino_launch/param/pipeline_object.yaml +++ b/vino_launch/param/pipeline_object.yaml @@ -1,6 +1,6 @@ Pipelines: - name: object - inputs: [RealSenseCamera] + inputs: [StandardCamera] infers: - name: ObjectDetection model: /opt/intel/computer_vision_sdk/deployment_tools/model_downloader/object_detection/common/ssd/300/caffe/output/ssd300.xml @@ -10,7 +10,7 @@ Pipelines: outputs: [ImageWindow, RosTopic, RViz] confidence_threshold: 0.5 connects: - - left: RealSenseCamera + - left: StandardCamera right: [ObjectDetection] - left: ObjectDetection right: [ImageWindow] diff --git a/vino_param_lib/include/vino_param_lib/param_manager.h b/vino_param_lib/include/vino_param_lib/param_manager.h index 7166d933..1f0a5cc3 100644 --- a/vino_param_lib/include/vino_param_lib/param_manager.h +++ b/vino_param_lib/include/vino_param_lib/param_manager.h @@ -51,9 +51,7 @@ class ParamManager // singleton */ static ParamManager& getInstance() { - std::cout << "getting instance" << std::endl; static ParamManager manager_; - std::cout << "return instance" << std::endl; return manager_; } From 00b09f74fb8cc95d6e650f0ad65f4448c6254702 Mon Sep 17 00:00:00 2001 From: luyang00 <393780933@qq.com> Date: Tue, 26 Mar 2019 13:06:23 +0800 Subject: [PATCH 05/15] add rostopic output for segmentation and person-reid --- README.md | 11 +++- .../outputs/ros_topic_output.h | 20 ++++++ .../src/outputs/ros_topic_output.cpp | 64 +++++++++++++++++++ people_msgs/CMakeLists.txt | 4 ++ people_msgs/msg/ObjectInMask.msg | 19 ++++++ people_msgs/msg/ObjectsInMasks.msg | 17 +++++ people_msgs/msg/Reidentification.msg | 17 +++++ people_msgs/msg/ReidentificationStamped.msg | 17 +++++ 8 files changed, 168 insertions(+), 1 deletion(-) create mode 100644 people_msgs/msg/ObjectInMask.msg create mode 100644 people_msgs/msg/ObjectsInMasks.msg create mode 100644 people_msgs/msg/Reidentification.msg create mode 100644 people_msgs/msg/ReidentificationStamped.msg diff --git a/README.md b/README.md index e74beb96..98148da9 100644 --- a/README.md +++ b/README.md @@ -26,7 +26,7 @@ From the view of logic implementation, the package introduces the definitions of ![Logic_Flow](https://github.com/intel/ros_openvino_toolkit/blob/devel/data/images/impletation_logic.PNG "OpenVINO RunTime Logic Flow") -Once a corresponding program is launched with a specified .yaml config file passed in the .launch.py file or via commandline, _**parameter manager**_ analyzes the configurations about pipeline and the whole framework, then shares the parsed configuration information with pipeline procedure. A _**pipeline instance**_ is created by following the configuration info and is added into _**pipeline manager**_ for lifecycle control and inference action triggering. +Once a corresponding program is launched with a specified .yaml config file passed in the .launch file or via commandline, _**parameter manager**_ analyzes the configurations about pipeline and the whole framework, then shares the parsed configuration information with pipeline procedure. A _**pipeline instance**_ is created by following the configuration info and is added into _**pipeline manager**_ for lifecycle control and inference action triggering. The contents in **.yaml config file** should be well structured and follow the supported rules and entity names. Please see [the configuration guidance](https://github.com/intel/ros_openvino_toolkit/blob/devel/doc/YAML_CONFIGURATION_GUIDE.md) for how to create or edit the config files. @@ -58,6 +58,7 @@ Currently, the inference feature list is supported: |Object Detection| object detection based on SSD-based trained models.| |Vehicle Detection| Vehicle and passenger detection based on Intel models.| |Object Segmentation| object detection and segmentation.| +|Person Reidentification| Person Reidentification based on object detection.| ## ROS interfaces and outputs ### Topic @@ -77,6 +78,8 @@ Currently, the inference feature list is supported: ```/ros_openvino_toolkit/detected_objects```([object_msgs::ObjectsInBoxes](https://github.com/intel/object_msgs/blob/master/msg/ObjectsInBoxes.msg)) - Object Segmentation: ```/ros_openvino_toolkit/segmented_obejcts```([people_msgs::ObjectsInMasks](https://github.com/intel/ros_openvino_toolkit/blob/devel/people_msgs/msg/ObjectsInMasks.msg)) +- Person Reidentification: +```/ros_openvino_toolkit/reidentified_persons```([people_msgs::ReidentificationStamped](https://github.com/intel/ros_openvino_toolkit/blob/devel/people_msgs/msg/ReidentificationStamped.msg)) - Rviz Output: ```/ros_openvino_toolkit/image_rviz```([sensor_msgs::Image](http://docs.ros.org/melodic/api/sensor_msgs/html/msg/Image.html)) @@ -109,6 +112,12 @@ See below pictures for the demo result snapshots. * object detection input from realsense camera ![object_detection_demo_realsense](https://github.com/intel/ros_openvino_toolkit/blob/devel/data/images/object_detection.gif "object detection demo realsense") +* object segmentation input from video +![object_segmentation_demo_video](https://github.com/intel/ros_openvino_toolkit/blob/devel/data/images/object_segmentation.gif "object segmentation demo video") + +* Person Reidentification input from standard camera +![person_reidentification_demo_video](https://github.com/intel/ros2_openvino_toolkit/blob/devel/data/images/person-reidentification.gif "person reidentification demo video") + # Installation & Launching **NOTE:** Intel releases 2 different series of OpenVINO Toolkit, we call them as [OpenSource Version](https://github.com/opencv/dldt/) and [Tarball Version](https://software.intel.com/en-us/openvino-toolkit). This guidelie uses OpenSource Version as the installation and launching example. **If you want to use Tarball version, please follow [the guide for Tarball Version](https://github.com/intel/ros_openvino_toolkit/blob/devel/doc/BINARY_VERSION_README.md).** diff --git a/dynamic_vino_lib/include/dynamic_vino_lib/outputs/ros_topic_output.h b/dynamic_vino_lib/include/dynamic_vino_lib/outputs/ros_topic_output.h index 0486df9c..583c9afd 100644 --- a/dynamic_vino_lib/include/dynamic_vino_lib/outputs/ros_topic_output.h +++ b/dynamic_vino_lib/include/dynamic_vino_lib/outputs/ros_topic_output.h @@ -32,6 +32,10 @@ #include #include #include +#include +#include +#include +#include #include #include @@ -61,6 +65,18 @@ class RosTopicOutput : public BaseOutput * functions with ros topic. */ void handleOutput() override; + /** + * @brief Generate ros topic infomation according to + * the person reidentification result. + * @param[in] results a bundle of person reidentification results. + */ + void accept(const std::vector &) override; + /** + * @brief Generate ros topic infomation according to + * the object segmentation result. + * @param[in] results a bundle of object segmentation results. + */ + void accept(const std::vector &) override; /** * @brief Generate ros topic infomation according to * the face detection result. @@ -110,6 +126,10 @@ class RosTopicOutput : public BaseOutput std::shared_ptr headpose_msg_ptr_; ros::Publisher pub_object_; std::shared_ptr object_msg_ptr_; + ros::Publisher pub_person_reid_; + std::shared_ptr person_reid_msg_ptr_; + ros::Publisher pub_segmented_object_; + std::shared_ptr segmented_object_msg_ptr_; }; } // namespace Outputs diff --git a/dynamic_vino_lib/src/outputs/ros_topic_output.cpp b/dynamic_vino_lib/src/outputs/ros_topic_output.cpp index 7ad30f21..04496148 100644 --- a/dynamic_vino_lib/src/outputs/ros_topic_output.cpp +++ b/dynamic_vino_lib/src/outputs/ros_topic_output.cpp @@ -37,16 +37,65 @@ Outputs::RosTopicOutput::RosTopicOutput() "/openvino_toolkit/headposes", 16); pub_object_ = nh_.advertise( "/openvino_toolkit/objects", 16); + pub_person_reid_ = nh_.advertise( + "/openvino_toolkit/reidentified_persons", 16); + pub_segmented_object_ = nh_.advertise( + "/openvino_toolkit/segmented_obejcts", 16); emotions_msg_ptr_ = NULL; faces_msg_ptr_ = NULL; age_gender_msg_ptr_ = NULL; headpose_msg_ptr_ = NULL; object_msg_ptr_ = NULL; + person_reid_msg_ptr_ = NULL; + segmented_object_msg_ptr_ = NULL; } void Outputs::RosTopicOutput::feedFrame(const cv::Mat& frame) {} + +void Outputs::RosTopicOutput::accept( + const std::vector & results) +{ + person_reid_msg_ptr_ = std::make_shared(); + people_msgs::Reidentification person; + for (auto & r : results) { + // slog::info << ">"; + auto loc = r.getLocation(); + person.roi.x_offset = loc.x; + person.roi.y_offset = loc.y; + person.roi.width = loc.width; + person.roi.height = loc.height; + person.identity = r.getPersonID(); + person_reid_msg_ptr_->reidentified_vector.push_back(person); + } +} + +void Outputs::RosTopicOutput::accept( + const std::vector & results) +{ + segmented_object_msg_ptr_ = std::make_shared(); + people_msgs::ObjectInMask object; + for (auto & r : results) { + // slog::info << ">"; + auto loc = r.getLocation(); + object.roi.x_offset = loc.x; + object.roi.y_offset = loc.y; + object.roi.width = loc.width; + object.roi.height = loc.height; + object.object_name = r.getLabel(); + object.probability = r.getConfidence(); + cv::Mat mask = r.getMask(); + for (int h = 0; h < mask.size().height; ++h) { + for (int w = 0; w < mask.size().width; ++w) { + object.mask_array.push_back(mask.at(h, w)); + } + } + segmented_object_msg_ptr_->objects_vector.push_back(object); + } +} + + void Outputs::RosTopicOutput::accept( const std::vector& results) { @@ -155,6 +204,21 @@ void Outputs::RosTopicOutput::accept( void Outputs::RosTopicOutput::handleOutput() { std_msgs::Header header = getHeader(); + if (person_reid_msg_ptr_ != nullptr) { + people_msgs::ReidentificationStamped person_reid_msg; + person_reid_msg.header = header; + person_reid_msg.reidentified_vector.swap(person_reid_msg_ptr_->reidentified_vector); + pub_person_reid_.publish(person_reid_msg); + person_reid_msg_ptr_ = nullptr; + } + if (segmented_object_msg_ptr_ != nullptr) { + // slog::info << "publishing faces outputs." << slog::endl; + people_msgs::ObjectsInMasks segmented_msg; + segmented_msg.header = header; + segmented_msg.objects_vector.swap(segmented_object_msg_ptr_->objects_vector); + pub_segmented_object_.publish(segmented_msg); + segmented_object_msg_ptr_ = nullptr; + } if (faces_msg_ptr_ != NULL) { object_msgs::ObjectsInBoxes faces_msg; diff --git a/people_msgs/CMakeLists.txt b/people_msgs/CMakeLists.txt index a2c13e68..bafaa681 100644 --- a/people_msgs/CMakeLists.txt +++ b/people_msgs/CMakeLists.txt @@ -31,6 +31,10 @@ add_message_files(DIRECTORY msg FILES HeadPose.msg HeadPoseStamped.msg PersonsStamped.msg + ObjectInMask.msg + ObjectsInMasks.msg + Reidentification.msg + ReidentificationStamped.msg ) add_service_files(FILES diff --git a/people_msgs/msg/ObjectInMask.msg b/people_msgs/msg/ObjectInMask.msg new file mode 100644 index 00000000..aa981eef --- /dev/null +++ b/people_msgs/msg/ObjectInMask.msg @@ -0,0 +1,19 @@ +# Copyright (c) 2017 Intel Corporation +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +# This message can represent a detected object and its region of interest +string object_name # object name +float32 probability # probability of detected object +sensor_msgs/RegionOfInterest roi # region of interest +float32[] mask_array # Instance mask as Image \ No newline at end of file diff --git a/people_msgs/msg/ObjectsInMasks.msg b/people_msgs/msg/ObjectsInMasks.msg new file mode 100644 index 00000000..28bd3eb2 --- /dev/null +++ b/people_msgs/msg/ObjectsInMasks.msg @@ -0,0 +1,17 @@ +# Copyright (c) 2017 Intel Corporation +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +# This message can represent objects detected and their bounding-boxes in a frame +std_msgs/Header header # timestamp in header is the time the sensor captured the raw data +ObjectInMask[] objects_vector # ObjectInBox array diff --git a/people_msgs/msg/Reidentification.msg b/people_msgs/msg/Reidentification.msg new file mode 100644 index 00000000..a3de50ec --- /dev/null +++ b/people_msgs/msg/Reidentification.msg @@ -0,0 +1,17 @@ +# Copyright (c) 2017 Intel Corporation +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +# This message can represent a reidentified person and its ID +string identity # person ID +sensor_msgs/RegionOfInterest roi # region of interest \ No newline at end of file diff --git a/people_msgs/msg/ReidentificationStamped.msg b/people_msgs/msg/ReidentificationStamped.msg new file mode 100644 index 00000000..cba3c33e --- /dev/null +++ b/people_msgs/msg/ReidentificationStamped.msg @@ -0,0 +1,17 @@ +# Copyright (c) 2017 Intel Corporation +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +# This message can represent reidentified persons and its IDs +std_msgs/Header header # timestamp in header is the time the sensor captured the raw data +Reidentification[] reidentified_vector # ObjectInBox array \ No newline at end of file From adea190819d652b1ca8e9bb6612a99e615973c0b Mon Sep 17 00:00:00 2001 From: luyang00 <393780933@qq.com> Date: Tue, 26 Mar 2019 15:50:20 +0800 Subject: [PATCH 06/15] update docs and launch files --- README.md | 40 ++- .../inferences/object_detection.h | 2 +- .../src/inferences/object_detection.cpp | 3 +- dynamic_vino_lib/src/pipeline_manager.cpp | 2 +- sample/CMakeLists.txt | 38 --- sample/src/image_object_server.cpp | 7 +- sample/src/image_people_server.cpp | 8 +- sample/src/sample_pipeline_object.cpp | 196 ------------- sample/src/sample_pipeline_people.cpp | 272 ------------------ vino_launch/launch/image_object_server.launch | 7 +- .../launch/image_object_server_oss.launch | 9 + vino_launch/launch/image_people_server.launch | 7 +- .../launch/image_people_server_oss.launch | 9 + vino_launch/launch/pipeline_image.launch | 8 + vino_launch/launch/pipeline_image_oss.launch | 8 + .../launch/pipeline_object_myriad.launch | 13 + .../launch/pipeline_object_oss_topic.launch | 13 + vino_launch/launch/pipeline_param.launch | 2 +- .../pipeline_reidentification_oss.launch | 8 + .../launch/pipeline_segementation.launch | 8 + vino_launch/launch/pipeline_video.launch | 8 + vino_launch/param/image_object_server.yaml | 2 +- .../param/image_object_server_oss.yaml | 18 ++ vino_launch/param/image_people_server.yaml | 8 +- ..._oos.yaml => image_people_server_oss.yaml} | 10 +- vino_launch/param/pipeline_image.yaml | 40 +++ vino_launch/param/pipeline_image_oss.yaml | 40 +++ vino_launch/param/pipeline_object_myriad.yaml | 22 ++ .../param/pipeline_object_oss_topic.yaml | 22 ++ .../param/pipeline_reidentification.yaml | 12 +- .../param/pipeline_reidentification_oss.yaml | 27 ++ vino_launch/param/pipeline_segmentation.yaml | 8 +- vino_launch/param/pipeline_video.yaml | 20 ++ 33 files changed, 337 insertions(+), 560 deletions(-) delete mode 100644 sample/src/sample_pipeline_object.cpp delete mode 100644 sample/src/sample_pipeline_people.cpp create mode 100644 vino_launch/launch/image_object_server_oss.launch create mode 100644 vino_launch/launch/image_people_server_oss.launch create mode 100644 vino_launch/launch/pipeline_image.launch create mode 100644 vino_launch/launch/pipeline_image_oss.launch create mode 100644 vino_launch/launch/pipeline_object_myriad.launch create mode 100644 vino_launch/launch/pipeline_object_oss_topic.launch create mode 100644 vino_launch/launch/pipeline_reidentification_oss.launch create mode 100644 vino_launch/launch/pipeline_segementation.launch create mode 100644 vino_launch/launch/pipeline_video.launch create mode 100644 vino_launch/param/image_object_server_oss.yaml rename vino_launch/param/{pipeline_people_oos.yaml => image_people_server_oss.yaml} (87%) create mode 100644 vino_launch/param/pipeline_image.yaml create mode 100644 vino_launch/param/pipeline_image_oss.yaml create mode 100644 vino_launch/param/pipeline_object_myriad.yaml create mode 100644 vino_launch/param/pipeline_object_oss_topic.yaml create mode 100644 vino_launch/param/pipeline_reidentification_oss.yaml create mode 100644 vino_launch/param/pipeline_video.yaml diff --git a/README.md b/README.md index 98148da9..63e1728b 100644 --- a/README.md +++ b/README.md @@ -89,11 +89,11 @@ Currently, the inference feature list is supported: - Face Detection Service: ```/detect_face``` ([object_msgs::DetectObject](https://github.com/intel/object_msgs/blob/master/srv/DetectObject.srv)) - Age & Gender Detection Service: -```/detect_age_gender``` ([people_msgs::AgeGender](https://github.com/intel/ros_openvino_toolkit/blob/devel/people_msgs/srv/AgeGender.srv)) +```/detect_age_gender``` ([people_msgs::AgeGender](https://github.com/intel/ros_openvino_toolkit/blob/devel/people_msgs/srv/AgeGenderSrv.srv)) - Headpose Detection Service: -```/detect_head_pose``` ([people_msgs::HeadPose](https://github.com/intel/ros_openvino_toolkit/blob/devel/people_msgs/srv/HeadPose.srv)) +```/detect_head_pose``` ([people_msgs::HeadPose](https://github.com/intel/ros_openvino_toolkit/blob/devel/people_msgs/srv/HeadPoseSrv.srv)) - Emotion Detection Service: -```/detect_emotion``` ([people_msgs::Emotion](https://github.com/intel/ros_openvino_toolkit/blob/devel/people_msgs/srv/Emotion.srv)) +```/detect_emotion``` ([people_msgs::Emotion](https://github.com/intel/ros_openvino_toolkit/blob/devel/people_msgs/srv/EmotionSrv.srv)) ### RViz RViz dispaly is also supported by the composited topic of original image frame with inference result. @@ -167,11 +167,41 @@ One-step installation scripts are provided for the dependencies' installation. P roslaunch vino_launch pipeline_people_oss.launch ``` -* run object detection sample code input from RealsensCamera. +* run object detection sample code input from RealsensCamera.(connect Intel® Neural Compute Stick 2) ```bash - roslaunch vino_launch pipeline_object_oss.launch + roslaunch vino_launch pipeline_object_myriad.launch ``` +* run object segmentation sample code input from RealSenseCameraTopic. + ```bash + roslaunch vino_launch pipeline_segmentation.launch + ``` +* run object segmentation sample code input from Video. + ```bash + roslaunch vino_launch pipeline_video.launch + ``` +* run person reidentification sample code input from StandardCamera. + ```bash + roslaunch vino_launch pipeline_reidentification_oss.launch + ``` +* run object detection service sample code input from Image + Run image processing service: + ```bash + roslaunch vino_launch image_object_server_oss.launch + ``` + Run example application with an absolute path of an image on another console: + ```bash + rosrun dynamic_vino_sample image_object_client ~/catkin_ws/src/ros_openvino_toolkit/data/images/car.png + ``` +* run face detection service sample code input from Image + Run image processing service: + ```bash + roslaunch vino_launch image_people_server_oss.launch + ``` + Run example application with an absolute path of an image on another console: + ```bash + rosrun dynamic_vino_sample image_people_client + ``` # TODO Features * Support **result filtering** for inference process, so that the inference results can be filtered to different subsidiary inference. For example, given an image, firstly we do Object Detection on it, secondly we pass cars to vehicle brand recognition and pass license plate to license number recognition. * Design **resource manager** to better use such resources as models, engines, and other external plugins. diff --git a/dynamic_vino_lib/include/dynamic_vino_lib/inferences/object_detection.h b/dynamic_vino_lib/include/dynamic_vino_lib/inferences/object_detection.h index 30d12d26..6eb50efa 100644 --- a/dynamic_vino_lib/include/dynamic_vino_lib/inferences/object_detection.h +++ b/dynamic_vino_lib/include/dynamic_vino_lib/inferences/object_detection.h @@ -57,7 +57,7 @@ class ObjectDetectionResult : public Result { class ObjectDetection : public BaseInference { public: using Result = dynamic_vino_lib::ObjectDetectionResult; - explicit ObjectDetection(double); + explicit ObjectDetection(bool,double); ~ObjectDetection() override; /** * @brief Load the face detection model. diff --git a/dynamic_vino_lib/src/inferences/object_detection.cpp b/dynamic_vino_lib/src/inferences/object_detection.cpp index 752c206d..f25259bc 100644 --- a/dynamic_vino_lib/src/inferences/object_detection.cpp +++ b/dynamic_vino_lib/src/inferences/object_detection.cpp @@ -29,7 +29,8 @@ dynamic_vino_lib::ObjectDetectionResult::ObjectDetectionResult( const cv::Rect& location) : Result(location){} // ObjectDetection -dynamic_vino_lib::ObjectDetection::ObjectDetection(double show_output_thresh) +dynamic_vino_lib::ObjectDetection::ObjectDetection(bool enable_roi_constraint, + double show_output_thresh) : dynamic_vino_lib::BaseInference(), show_output_thresh_(show_output_thresh){} dynamic_vino_lib::ObjectDetection::~ObjectDetection() = default; diff --git a/dynamic_vino_lib/src/pipeline_manager.cpp b/dynamic_vino_lib/src/pipeline_manager.cpp index 42e173bd..2da27143 100644 --- a/dynamic_vino_lib/src/pipeline_manager.cpp +++ b/dynamic_vino_lib/src/pipeline_manager.cpp @@ -285,7 +285,7 @@ const Params::ParamManager::InferenceParams & infer) auto object_detection_engine = std::make_shared( plugins_for_devices_[infer.engine], object_detection_model); auto object_inference_ptr = std::make_shared( - 0.5); // To-do theshold configuration + infer.enable_roi_constraint, infer.confidence_threshold); // To-do theshold configuration object_inference_ptr->loadNetwork(object_detection_model); object_inference_ptr->loadEngine(object_detection_engine); diff --git a/sample/CMakeLists.txt b/sample/CMakeLists.txt index f59593b9..0e918807 100644 --- a/sample/CMakeLists.txt +++ b/sample/CMakeLists.txt @@ -97,44 +97,6 @@ set_target_properties(gflags PROPERTIES set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11") -add_executable(sample_pipeline_people - src/sample_pipeline_people.cpp -) - -add_dependencies(sample_pipeline_people - ${${PROJECT_NAME}_EXPORTED_TARGETS} - ${catkin_EXPORTED_TARGETS} - ${dynamic_vino_lib_TARGETS} -) - -target_link_libraries(sample_pipeline_people - ${catkin_LIBRARIES} - cpu_extension - gflags - ${vino_param_lib_LIBRARIES} - ${InferenceEngine_LIBRARIES} - ${OpenCV_LIBRARIES} -) - -add_executable(sample_pipeline_object - src/sample_pipeline_object.cpp -) - -add_dependencies(sample_pipeline_object - ${${PROJECT_NAME}_EXPORTED_TARGETS} - ${catkin_EXPORTED_TARGETS} - ${dynamic_vino_lib_TARGETS} -) - -target_link_libraries(sample_pipeline_object - ${catkin_LIBRARIES} - cpu_extension - gflags - ${vino_param_lib_LIBRARIES} - ${InferenceEngine_LIBRARIES} - ${OpenCV_LIBRARIES} -) - add_executable(pipeline_with_params src/pipeline_with_params.cpp ) diff --git a/sample/src/image_object_server.cpp b/sample/src/image_object_server.cpp index 51754dec..25905814 100644 --- a/sample/src/image_object_server.cpp +++ b/sample/src/image_object_server.cpp @@ -78,13 +78,8 @@ int main(int argc, char** argv) if (!parseAndCheckCommandLine(argc, argv)) return 0; - std::string param_path = ""; - ros::param::param("~param_file", param_path, "/param/pipeline_people.yaml"); - std::cout<("~param_file", FLAGS_config, "/param/pipeline_people.yaml"); - prefix_path = ros::package::getPath("vino_launch"); - FLAGS_config = prefix_path + param_path; slog::info << "FLAGS_config=" << FLAGS_config << slog::endl; std::string service_name = "/openvino_toolkit/service"; diff --git a/sample/src/image_people_server.cpp b/sample/src/image_people_server.cpp index 7e7bd95b..92520ec5 100644 --- a/sample/src/image_people_server.cpp +++ b/sample/src/image_people_server.cpp @@ -80,13 +80,7 @@ int main(int argc, char** argv) if (!parseAndCheckCommandLine(argc, argv)) return 0; - std::string param_path = ""; - ros::param::param("~param_file", param_path, "/param/pipeline_people.yaml"); - - std::string prefix_path; - prefix_path = ros::package::getPath("vino_launch"); - - FLAGS_config = prefix_path + param_path; + ros::param::param("~param_file", FLAGS_config, "/param/pipeline_people.yaml"); slog::info << "FLAGS_config=" << FLAGS_config << slog::endl; diff --git a/sample/src/sample_pipeline_object.cpp b/sample/src/sample_pipeline_object.cpp deleted file mode 100644 index 80f53d59..00000000 --- a/sample/src/sample_pipeline_object.cpp +++ /dev/null @@ -1,196 +0,0 @@ -/* - * Copyright (c) 2018 Intel Corporation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ -/** -* \brief A sample for this library. This sample performs face detection, - * emotions detection, age gender detection and head pose estimation. -* \file sample/main.cpp -*/ - -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include "dynamic_vino_lib/common.h" -#include "dynamic_vino_lib/engines/engine.h" -#include "dynamic_vino_lib/factory.h" -#include "dynamic_vino_lib/inferences/age_gender_detection.h" -#include "dynamic_vino_lib/inferences/base_inference.h" -#include "dynamic_vino_lib/inferences/emotions_detection.h" -#include "dynamic_vino_lib/inferences/face_detection.h" -#include "dynamic_vino_lib/inferences/head_pose_detection.h" -#include "dynamic_vino_lib/inputs/realsense_camera_topic.h" -#include "dynamic_vino_lib/outputs/image_window_output.h" -#include "dynamic_vino_lib/outputs/ros_topic_output.h" -#include "dynamic_vino_lib/outputs/rviz_output.h" -#include "dynamic_vino_lib/pipeline.h" -#include "dynamic_vino_lib/slog.h" -#include "inference_engine.hpp" -#include "librealsense2/rs.hpp" -#include "opencv2/opencv.hpp" -#include "sample/utility.hpp" - -bool parseAndCheckCommandLine(int argc, char** argv) -{ - // ---------------------------Parsing and validation of input - // args----------------------------- - gflags::ParseCommandLineNonHelpFlags(&argc, &argv, true); - if (FLAGS_h) - { - showUsageForParam(); - return false; - } - - return true; -} - -int main(int argc, char* argv[]) -{ - ros::init(argc, argv, "sample_pipeline_object"); - ros::NodeHandle n; - std::string content; - std::string prefix_path; - - prefix_path = ros::package::getPath("vino_launch"); - FLAGS_config = prefix_path + "/param/pipeline_object.yaml"; - - slog::info << "prefix_path=" << prefix_path << slog::endl; - - try - { - std::cout << "InferenceEngine: " - << InferenceEngine::GetInferenceEngineVersion() << std::endl; - // ------------------------------ Parsing and validation of input args - // ------------------------- - if (!parseAndCheckCommandLine(argc, argv)) - { - return 0; - } - - Params::ParamManager::getInstance().parse(FLAGS_config); - Params::ParamManager::getInstance().print(); - - auto pcommon = Params::ParamManager::getInstance().getCommon(); - auto pipelines = Params::ParamManager::getInstance().getPipelines(); - if (pipelines.size() < 1) { - throw std::logic_error("Pipeline parameters should be set!"); - } - - FLAGS_i = pipelines[0].inputs[0]; - FLAGS_d = pipelines[0].infers[0].engine; - FLAGS_m = pipelines[0].infers[0].model; - FLAGS_c = pcommon.custom_cldnn_library; - - // ----------- 1. Load Plugin for inference engine - //std::unique_ptr plugin = Factory::makePluginByName( - // FLAGS_d, FLAGS_l, FLAGS_c, FLAGS_pc); - std::map plugins_for_devices; - std::vector> cmd_options = - { - {FLAGS_d, FLAGS_m}, - {FLAGS_d_ag, FLAGS_m_ag}, - {FLAGS_d_hp, FLAGS_m_hp}, - {FLAGS_d_em, FLAGS_m_em} - }; - slog::info << "device_FACE:" << FLAGS_d << slog::endl; - slog::info << "model_FACE:" << FLAGS_m << slog::endl; - slog::info << "device_AG:" << FLAGS_d_ag << slog::endl; - slog::info << "model_AG:" << FLAGS_m_ag << slog::endl; - slog::info << "model_HeadPose:" << FLAGS_m_hp << slog::endl; - slog::info << "device_HeadPose:" << FLAGS_d_hp << slog::endl; - - for (auto&& option : cmd_options) - { - auto device_name = option.first; - auto network_name = option.second; - if (device_name.empty() || network_name.empty()) - { - continue; - } - if (plugins_for_devices.find(device_name) != plugins_for_devices.end()) - { - continue; - } - plugins_for_devices[device_name] = - *Factory::makePluginByName(device_name, FLAGS_l, FLAGS_c, FLAGS_pc); - } - - // --------------------------- 2. Generate Input Device and Output - // Device----------------------- - slog::info << "Reading input" << slog::endl; - auto input_ptr = Factory::makeInputDeviceByName(FLAGS_i, FLAGS_i_path); - - if (!input_ptr->initialize()) { - throw std::logic_error("Cannot open input file or camera: " + FLAGS_i); - } - std::string window_name = "Results"; - auto output_ptr = std::make_shared(window_name); - // --------------------------- 3. Generate Inference - // Instance----------------------------------- - // generate face detection inference - auto model = - std::make_shared(FLAGS_m, 1, 1, 1); - model->modelInit(); - auto engine = std::make_shared(plugins_for_devices[FLAGS_d], model); - auto object_detection_ptr = - std::make_shared(FLAGS_t); - object_detection_ptr->loadNetwork(model); - object_detection_ptr->loadEngine(engine); - slog::info << "Pass Inference Prep." << slog::endl; - // ------- 4. Build Pipeline ------------- - Pipeline pipe; - pipe.add("video_input", input_ptr); - pipe.add("video_input", "object_detection", object_detection_ptr); - pipe.add("object_detection", "video_output", output_ptr); - auto ros_topic_output_ptr = std::make_shared(); - auto rviz_output_ptr = std::make_shared(); - pipe.add("object_detection", "ros_output", ros_topic_output_ptr); - pipe.add("object_detection", "rviz_output", rviz_output_ptr); - pipe.setCallback(); - pipe.printPipeline(); - - slog::info << "Pass Pipeline Init." << slog::endl; - - // ------- 5. Run Pipeline ----------- - while (cv::waitKey(1) < 0 && ros::ok()) - { - ros::spinOnce(); - pipe.runOnce(); - } - - slog::info << "Execution successful" << slog::endl; - return 0; - } catch (const std::exception& error) { - slog::err << error.what() << slog::endl; - return 1; - } catch (...) { - slog::err << "Unknown/internal exception happened." << slog::endl; - return 1; - } -} diff --git a/sample/src/sample_pipeline_people.cpp b/sample/src/sample_pipeline_people.cpp deleted file mode 100644 index 1e1a3310..00000000 --- a/sample/src/sample_pipeline_people.cpp +++ /dev/null @@ -1,272 +0,0 @@ -/* - * Copyright (c) 2018 Intel Corporation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -/** -* \brief A sample for this library. This sample performs face detection, - * emotions detection, age gender detection and head pose estimation. -* \file sample/main.cpp -*/ - -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include -#include "dynamic_vino_lib/common.h" -#include "dynamic_vino_lib/engines/engine.h" -#include "dynamic_vino_lib/factory.h" -#include "dynamic_vino_lib/inferences/age_gender_detection.h" -#include "dynamic_vino_lib/inferences/base_inference.h" -#include "dynamic_vino_lib/inferences/emotions_detection.h" -#include "dynamic_vino_lib/inferences/face_detection.h" -#include "dynamic_vino_lib/inferences/head_pose_detection.h" -#include "dynamic_vino_lib/inputs/realsense_camera_topic.h" -#include "dynamic_vino_lib/outputs/image_window_output.h" -#include "dynamic_vino_lib/outputs/ros_topic_output.h" -#include "dynamic_vino_lib/outputs/rviz_output.h" -#include "dynamic_vino_lib/pipeline.h" -#include "dynamic_vino_lib/slog.h" -#include "inference_engine.hpp" -#include "opencv2/opencv.hpp" -#include "sample/utility.hpp" - -bool parseAndCheckCommandLine(int argc, char** argv) -{ - // -----Parsing and validation of input args--------------------------- - gflags::ParseCommandLineNonHelpFlags(&argc, &argv, true); - if (FLAGS_h) - { - showUsageForParam(); - return false; - } - - return true; -} - -int main(int argc, char** argv) -{ - ros::init(argc, argv, "sample_pipeline_people"); - ros::NodeHandle n; - std::string content; - std::string prefix_path; - - prefix_path = ros::package::getPath("vino_launch"); - FLAGS_config = prefix_path + "/param/pipeline_people.yaml"; - - slog::info << "FLAGS_config=" << FLAGS_config << slog::endl; - - try - { - std::cout << "InferenceEngine: " - << InferenceEngine::GetInferenceEngineVersion() << std::endl; - - // ----- Parsing and validation of input args----------------------- - if (!parseAndCheckCommandLine(argc, argv)) - { - return 0; - } - - Params::ParamManager::getInstance().parse(FLAGS_config); - Params::ParamManager::getInstance().print(); - - auto pcommon = Params::ParamManager::getInstance().getCommon(); - auto pipelines = Params::ParamManager::getInstance().getPipelines(); - if (pipelines.size() < 1) - { - throw std::logic_error("Pipeline parameters should be set!"); - } - FLAGS_l = pcommon.custom_cpu_library; - FLAGS_c = pcommon.custom_cldnn_library; - FLAGS_pc = pcommon.enable_performance_count; - - // Only use the first pipeline if there are several. - FLAGS_i = pipelines[0].inputs[0]; - - for (const auto& inf : pipelines[0].infers) - { - if (inf.name == "face_detection") - { - FLAGS_d = inf.engine; - FLAGS_m = inf.model; - } - else if (inf.name == "age_gender_detection") - { - FLAGS_d_ag = inf.engine; - FLAGS_m_ag = inf.model; - } - else if (inf.name == "head_pose_detection") - { - FLAGS_d_hp = inf.engine; - FLAGS_m_hp = inf.model; - } - else if (inf.name == "emotion_detection") - { - FLAGS_d_em = inf.engine; - FLAGS_m_em = inf.model; - } - } - - // ----- 1. Load Plugin for inference engine------------------------ - std::map plugins_for_devices; - std::vector> cmd_options = - { - {FLAGS_d, FLAGS_m}, - {FLAGS_d_ag, FLAGS_m_ag}, - {FLAGS_d_hp, FLAGS_m_hp}, - {FLAGS_d_em, FLAGS_m_em} - }; - slog::info << "device_FACE:" << FLAGS_d << slog::endl; - slog::info << "model_FACE:" << FLAGS_m << slog::endl; - slog::info << "device_AG:" << FLAGS_d_ag << slog::endl; - slog::info << "model_AG:" << FLAGS_m_ag << slog::endl; - slog::info << "model_HeadPose:" << FLAGS_m_hp << slog::endl; - slog::info << "device_HeadPose:" << FLAGS_d_hp << slog::endl; - - for (auto&& option : cmd_options) - { - auto device_name = option.first; - auto network_name = option.second; - if (device_name.empty() || network_name.empty()) - { - continue; - } - if (plugins_for_devices.find(device_name) != plugins_for_devices.end()) - { - continue; - } - plugins_for_devices[device_name] = - *Factory::makePluginByName(device_name, FLAGS_l, FLAGS_c, FLAGS_pc); - } - - // ----- 2. Generate Input Device and Output Device--------------------- - slog::info << "Reading input" << slog::endl; - auto input_ptr = Factory::makeInputDeviceByName(FLAGS_i, FLAGS_i_path); - if (!input_ptr->initialize()) - { - throw std::logic_error("Cannot open input file or camera: " + FLAGS_i); - } - std::string window_name = "Results"; - auto output_ptr = std::make_shared(window_name); - auto ros_topic_output_ptr = std::make_shared(); - auto rviz_output_ptr = std::make_shared(); - - // ----- 3. Generate Inference Instance----------------------------------- - // generate face detection inference - auto face_detection_model = - std::make_shared(FLAGS_m, 1, 1, 1); - face_detection_model->modelInit(); - auto face_detection_engine = std::make_shared( - plugins_for_devices[FLAGS_d], face_detection_model); - auto face_inference_ptr = - std::make_shared(FLAGS_t); - face_inference_ptr->loadNetwork(face_detection_model); - face_inference_ptr->loadEngine(face_detection_engine); - - // generate emotions detection inference - auto emotions_detection_model = - std::make_shared(FLAGS_m_em, 1, 1, 16); - emotions_detection_model->modelInit(); - auto emotions_detection_engine = std::make_shared( - plugins_for_devices[FLAGS_d_em], emotions_detection_model); - auto emotions_inference_ptr = - std::make_shared(); - emotions_inference_ptr->loadNetwork(emotions_detection_model); - emotions_inference_ptr->loadEngine(emotions_detection_engine); - - // generate age gender detection inference - auto agegender_detection_model = - std::make_shared(FLAGS_m_ag, 1, 2, 16); - agegender_detection_model->modelInit(); - auto agegender_detection_engine = std::make_shared( - plugins_for_devices[FLAGS_d_ag], agegender_detection_model); - auto agegender_inference_ptr = - std::make_shared(); - agegender_inference_ptr->loadNetwork(agegender_detection_model); - agegender_inference_ptr->loadEngine(agegender_detection_engine); - - // generate head pose estimation inference - auto headpose_detection_network = - std::make_shared(FLAGS_m_hp, 1, 3, 16); - headpose_detection_network->modelInit(); - auto headpose_detection_engine = std::make_shared( - plugins_for_devices[FLAGS_d_hp], headpose_detection_network); - auto headpose_inference_ptr = - std::make_shared(); - headpose_inference_ptr->loadNetwork(headpose_detection_network); - headpose_inference_ptr->loadEngine(headpose_detection_engine); - - // ------ 4. Build Pipeline -------------------------------------- - Pipeline pipe; - // pipe.add("video_input", std::move(input_ptr)); - - pipe.add("video_input", input_ptr); - pipe.add("video_input", "face_detection", face_inference_ptr); - pipe.add("face_detection", "emotions_detection", emotions_inference_ptr); - pipe.add("face_detection", "age_gender_detection", agegender_inference_ptr); - pipe.add("face_detection", "headpose_detection", headpose_inference_ptr); - pipe.add("emotions_detection", "video_output", output_ptr); - pipe.add("age_gender_detection", "video_output", output_ptr); - pipe.add("headpose_detection", "video_output", output_ptr); - pipe.add("face_detection", "video_output", output_ptr); - - pipe.add("face_detection", "ros_output", ros_topic_output_ptr); - pipe.add("emotions_detection", "ros_output", ros_topic_output_ptr); - pipe.add("age_gender_detection", "ros_output", ros_topic_output_ptr); - pipe.add("headpose_detection", "ros_output", ros_topic_output_ptr); - - pipe.add("face_detection", "rviz_output", rviz_output_ptr); - pipe.add("emotions_detection", "rviz_output", rviz_output_ptr); - pipe.add("age_gender_detection", "rviz_output", rviz_output_ptr); - pipe.add("headpose_detection", "rviz_output", rviz_output_ptr); - - pipe.setCallback(); - pipe.printPipeline(); - - // ------ 5. Run Pipeline ----------------------------------- - while (cv::waitKey(1) < 0 && ros::ok()) - { - ros::spinOnce(); - pipe.runOnce(); - } - - slog::info << "Execution successful" << slog::endl; - return 0; - } - catch (const std::exception& error) - { - slog::err << error.what() << slog::endl; - return 1; - } - catch (...) - { - slog::err << "Unknown/internal exception happened." << slog::endl; - return 1; - } -} diff --git a/vino_launch/launch/image_object_server.launch b/vino_launch/launch/image_object_server.launch index 7370f269..d8ed17cd 100644 --- a/vino_launch/launch/image_object_server.launch +++ b/vino_launch/launch/image_object_server.launch @@ -1,12 +1,7 @@ - + diff --git a/vino_launch/launch/image_object_server_oss.launch b/vino_launch/launch/image_object_server_oss.launch new file mode 100644 index 00000000..a2698e2b --- /dev/null +++ b/vino_launch/launch/image_object_server_oss.launch @@ -0,0 +1,9 @@ + + + + + + + + diff --git a/vino_launch/launch/image_people_server.launch b/vino_launch/launch/image_people_server.launch index 33d8d846..eacd85fa 100644 --- a/vino_launch/launch/image_people_server.launch +++ b/vino_launch/launch/image_people_server.launch @@ -1,12 +1,7 @@ - + diff --git a/vino_launch/launch/image_people_server_oss.launch b/vino_launch/launch/image_people_server_oss.launch new file mode 100644 index 00000000..0d9bcf8b --- /dev/null +++ b/vino_launch/launch/image_people_server_oss.launch @@ -0,0 +1,9 @@ + + + + + + + + diff --git a/vino_launch/launch/pipeline_image.launch b/vino_launch/launch/pipeline_image.launch new file mode 100644 index 00000000..162c50c1 --- /dev/null +++ b/vino_launch/launch/pipeline_image.launch @@ -0,0 +1,8 @@ + + + + + + + diff --git a/vino_launch/launch/pipeline_image_oss.launch b/vino_launch/launch/pipeline_image_oss.launch new file mode 100644 index 00000000..c9187e4f --- /dev/null +++ b/vino_launch/launch/pipeline_image_oss.launch @@ -0,0 +1,8 @@ + + + + + + + diff --git a/vino_launch/launch/pipeline_object_myriad.launch b/vino_launch/launch/pipeline_object_myriad.launch new file mode 100644 index 00000000..1a27eeb4 --- /dev/null +++ b/vino_launch/launch/pipeline_object_myriad.launch @@ -0,0 +1,13 @@ + + + + + + + + + + + + diff --git a/vino_launch/launch/pipeline_object_oss_topic.launch b/vino_launch/launch/pipeline_object_oss_topic.launch new file mode 100644 index 00000000..dfe85513 --- /dev/null +++ b/vino_launch/launch/pipeline_object_oss_topic.launch @@ -0,0 +1,13 @@ + + + + + + + + + + + + diff --git a/vino_launch/launch/pipeline_param.launch b/vino_launch/launch/pipeline_param.launch index 0f54f6fc..0e2031f8 100644 --- a/vino_launch/launch/pipeline_param.launch +++ b/vino_launch/launch/pipeline_param.launch @@ -1,5 +1,5 @@ - + diff --git a/vino_launch/launch/pipeline_reidentification_oss.launch b/vino_launch/launch/pipeline_reidentification_oss.launch new file mode 100644 index 00000000..e4ad103c --- /dev/null +++ b/vino_launch/launch/pipeline_reidentification_oss.launch @@ -0,0 +1,8 @@ + + + + + + + diff --git a/vino_launch/launch/pipeline_segementation.launch b/vino_launch/launch/pipeline_segementation.launch new file mode 100644 index 00000000..2e2f26d9 --- /dev/null +++ b/vino_launch/launch/pipeline_segementation.launch @@ -0,0 +1,8 @@ + + + + + + + diff --git a/vino_launch/launch/pipeline_video.launch b/vino_launch/launch/pipeline_video.launch new file mode 100644 index 00000000..8d48a4ef --- /dev/null +++ b/vino_launch/launch/pipeline_video.launch @@ -0,0 +1,8 @@ + + + + + + + diff --git a/vino_launch/param/image_object_server.yaml b/vino_launch/param/image_object_server.yaml index 9c096e84..749157fe 100644 --- a/vino_launch/param/image_object_server.yaml +++ b/vino_launch/param/image_object_server.yaml @@ -3,7 +3,7 @@ Pipelines: inputs: [Image] infers: - name: ObjectDetection - model: /opt/openvino_toolkit/open_model_zoo/model_downloader/object_detection/common/ssd/300/caffe/output/ssd300.xml + model: /opt/intel/computer_vision_sdk/deployment_tools/model_downloader/object_detection/common/ssd/300/caffe/output/ssd300.xml engine: CPU label: to/be/set/xxx.labels batch: 16 diff --git a/vino_launch/param/image_object_server_oss.yaml b/vino_launch/param/image_object_server_oss.yaml new file mode 100644 index 00000000..9c096e84 --- /dev/null +++ b/vino_launch/param/image_object_server_oss.yaml @@ -0,0 +1,18 @@ +Pipelines: +- name: object + inputs: [Image] + infers: + - name: ObjectDetection + model: /opt/openvino_toolkit/open_model_zoo/model_downloader/object_detection/common/ssd/300/caffe/output/ssd300.xml + engine: CPU + label: to/be/set/xxx.labels + batch: 16 + outputs: [RosService] + confidence_threshold: 0.2 + connects: + - left: Image + right: [ObjectDetection] + - left: ObjectDetection + right: [RosService] + input_path: "/opt/openvino_toolkit/ros_openvino_toolkit/data/images/car.png" +OpenvinoCommon: diff --git a/vino_launch/param/image_people_server.yaml b/vino_launch/param/image_people_server.yaml index 15380f3a..858e8afd 100644 --- a/vino_launch/param/image_people_server.yaml +++ b/vino_launch/param/image_people_server.yaml @@ -3,22 +3,22 @@ Pipelines: inputs: [StandardCamera] infers: - name: face_detection - model: /home/intel/code/open_model_zoo/model_downloader/Transportation/object_detection/face/pruned_mobilenet_reduced_ssd_shared_weights/dldt/face-detection-adas-0001.xml + model: /opt/intel/computer_vision_sdk/deployment_tools/model_downloader/Transportation/object_detection/face/pruned_mobilenet_reduced_ssd_shared_weights/dldt/face-detection-adas-0001.xml engine: CPU label: to/be/set/xxx.labels batch: 1 - name: age_gender_detection - model: /home/intel/code/open_model_zoo/model_downloader/Retail/object_attributes/age_gender/dldt/age-gender-recognition-retail-0013.xml + model: /opt/intel/computer_vision_sdk/deployment_tools/model_downloader/Retail/object_attributes/age_gender/dldt/age-gender-recognition-retail-0013.xml engine: CPU label: to/be/set/xxx.labels batch: 16 - name: emotion_detection - model: /home/intel/code/open_model_zoo/model_downloader/Retail/object_attributes/emotions_recognition/0003/dldt/emotions-recognition-retail-0003.xml + model: /opt/intel/computer_vision_sdk/deployment_tools/model_downloader/Retail/object_attributes/emotions_recognition/0003/dldt/emotions-recognition-retail-0003.xml engine: CPU label: to/be/set/xxx.labels batch: 16 - name: head_pose_detection - model: /home/intel/code/open_model_zoo/model_downloader/Transportation/object_attributes/headpose/vanilla_cnn/dldt/head-pose-estimation-adas-0001.xml + model: /opt/intel/computer_vision_sdk/deployment_tools/model_downloader/Transportation/object_attributes/headpose/vanilla_cnn/dldt/head-pose-estimation-adas-0001.xml engine: CPU label: to/be/set/xxx.labels batch: 16 diff --git a/vino_launch/param/pipeline_people_oos.yaml b/vino_launch/param/image_people_server_oss.yaml similarity index 87% rename from vino_launch/param/pipeline_people_oos.yaml rename to vino_launch/param/image_people_server_oss.yaml index 17f4772a..8f375dfd 100644 --- a/vino_launch/param/pipeline_people_oos.yaml +++ b/vino_launch/param/image_people_server_oss.yaml @@ -22,18 +22,18 @@ Pipelines: engine: CPU label: to/be/set/xxx.labels batch: 16 - outputs: [ImageWindow, RosTopic,RViz] + outputs: [RosService] confidence_threshold: 0.2 connects: - left: StandardCamera right: [face_detection] - left: face_detection - right: [age_gender_detection, emotion_detection, head_pose_detection, ImageWindow, RosTopic, Rviz] + right: [age_gender_detection, emotion_detection, head_pose_detection, RosService] - left: age_gender_detection - right: [ImageWindow, RosTopic,RViz] + right: [RosService] - left: emotion_detection - right: [ImageWindow, RosTopic,RViz] + right: [RosService] - left: head_pose_detection - right: [ImageWindow, RosTopic,RViz] + right: [RosService] OpenvinoCommon: diff --git a/vino_launch/param/pipeline_image.yaml b/vino_launch/param/pipeline_image.yaml new file mode 100644 index 00000000..27b6f570 --- /dev/null +++ b/vino_launch/param/pipeline_image.yaml @@ -0,0 +1,40 @@ +Pipelines: +- name: people + inputs: [Image] + input_path: /opt/openvino_toolkit/ros_openvino_toolkit/data/images/team.jpg + infers: + - name: face_detection + model: /opt/intel/computer_vision_sdk/deployment_tools/model_downloader/Transportation/object_detection/face/pruned_mobilenet_reduced_ssd_shared_weights/dldt/face-detection-adas-0001.xml + engine: CPU + label: to/be/set/xxx.labels + batch: 1 + - name: age_gender_detection + model: /opt/intel/computer_vision_sdk/deployment_tools/model_downloader/Retail/object_attributes/age_gender/dldt/age-gender-recognition-retail-0013.xml + engine: CPU + label: to/be/set/xxx.labels + batch: 16 + - name: emotion_detection + model: /opt/intel/computer_vision_sdk/deployment_tools/model_downloader/Retail/object_attributes/emotions_recognition/0003/dldt/emotions-recognition-retail-0003.xml + engine: CPU + label: to/be/set/xxx.labels + batch: 16 + - name: head_pose_detection + model: /opt/intel/computer_vision_sdk/deployment_tools/model_downloader/Transportation/object_attributes/headpose/vanilla_cnn/dldt/head-pose-estimation-adas-0001.xml + engine: CPU + label: to/be/set/xxx.labels + batch: 16 + outputs: [ImageWindow] + confidence_threshold: 0.2 + connects: + - left: Image + right: [face_detection] + - left: face_detection + right: [age_gender_detection, emotion_detection, head_pose_detection, ImageWindow] + - left: age_gender_detection + right: [ImageWindow] + - left: emotion_detection + right: [ImageWindow] + - left: head_pose_detection + right: [ImageWindow] + +OpenvinoCommon: diff --git a/vino_launch/param/pipeline_image_oss.yaml b/vino_launch/param/pipeline_image_oss.yaml new file mode 100644 index 00000000..2fc4352b --- /dev/null +++ b/vino_launch/param/pipeline_image_oss.yaml @@ -0,0 +1,40 @@ +Pipelines: +- name: people + inputs: [Image] + input_path: /opt/openvino_toolkit/ros_openvino_toolkit/data/images/team.jpg + infers: + - name: face_detection + model: /opt/openvino_toolkit/open_model_zoo/model_downloader/Transportation/object_detection/face/pruned_mobilenet_reduced_ssd_shared_weights/dldt/face-detection-adas-0001.xml + engine: CPU + label: to/be/set/xxx.labels + batch: 1 + - name: age_gender_detection + model: /opt/openvino_toolkit/open_model_zoo/model_downloader/Retail/object_attributes/age_gender/dldt/age-gender-recognition-retail-0013.xml + engine: CPU + label: to/be/set/xxx.labels + batch: 16 + - name: emotion_detection + model: /opt/openvino_toolkit/open_model_zoo/model_downloader/Retail/object_attributes/emotions_recognition/0003/dldt/emotions-recognition-retail-0003.xml + engine: CPU + label: to/be/set/xxx.labels + batch: 16 + - name: head_pose_detection + model: /opt/openvino_toolkit/open_model_zoo/model_downloader/Transportation/object_attributes/headpose/vanilla_cnn/dldt/head-pose-estimation-adas-0001.xml + engine: CPU + label: to/be/set/xxx.labels + batch: 16 + outputs: [ImageWindow] + confidence_threshold: 0.2 + connects: + - left: Image + right: [face_detection] + - left: face_detection + right: [age_gender_detection, emotion_detection, head_pose_detection, ImageWindow] + - left: age_gender_detection + right: [ImageWindow] + - left: emotion_detection + right: [ImageWindow] + - left: head_pose_detection + right: [ImageWindow] + +OpenvinoCommon: diff --git a/vino_launch/param/pipeline_object_myriad.yaml b/vino_launch/param/pipeline_object_myriad.yaml new file mode 100644 index 00000000..a1f0daa4 --- /dev/null +++ b/vino_launch/param/pipeline_object_myriad.yaml @@ -0,0 +1,22 @@ +Pipelines: +- name: object + inputs: [StandardCamera] + infers: + - name: ObjectDetection + model: /opt/openvino_toolkit/open_model_zoo/model_downloader/object_detection/common/mobilenet-ssd/caffe/output/FP32/mobilenet-ssd.xml + engine: MYRIAD + label: to/be/set/xxx.labels + batch: 16 + outputs: [ImageWindow, RosTopic, RViz] + confidence_threshold: 0.5 + connects: + - left: StandardCamera + right: [ObjectDetection] + - left: ObjectDetection + right: [ImageWindow] + - left: ObjectDetection + right: [RosTopic] + - left: ObjectDetection + right: [RViz] + +OpenvinoCommon: diff --git a/vino_launch/param/pipeline_object_oss_topic.yaml b/vino_launch/param/pipeline_object_oss_topic.yaml new file mode 100644 index 00000000..efbd678b --- /dev/null +++ b/vino_launch/param/pipeline_object_oss_topic.yaml @@ -0,0 +1,22 @@ +Pipelines: +- name: object + inputs: [RealSenseCameraTopic] + infers: + - name: ObjectDetection + model: /opt/openvino_toolkit/open_model_zoo/model_downloader/object_detection/common/ssd/300/caffe/output/ssd300.xml + engine: CPU + label: to/be/set/xxx.labels + batch: 16 + outputs: [ImageWindow, RosTopic, RViz] + confidence_threshold: 0.5 + connects: + - left: RealSenseCameraTopic + right: [ObjectDetection] + - left: ObjectDetection + right: [ImageWindow] + - left: ObjectDetection + right: [RosTopic] + - left: ObjectDetection + right: [RViz] + +OpenvinoCommon: diff --git a/vino_launch/param/pipeline_reidentification.yaml b/vino_launch/param/pipeline_reidentification.yaml index e498bc9c..0722e523 100644 --- a/vino_launch/param/pipeline_reidentification.yaml +++ b/vino_launch/param/pipeline_reidentification.yaml @@ -1,27 +1,27 @@ Pipelines: - name: object - inputs: [RealSenseCamera] + inputs: [StandardCamera] infers: - name: ObjectDetection - model: /home/intel/code/open_model_zoo/model_downloader/Retail/object_detection/pedestrian/rmnet_ssd/0013/dldt/person-detection-retail-0013.xml + model: /opt/intel/computer_vision_sdk/deployment_tools/model_downloader/Retail/object_detection/pedestrian/rmnet_ssd/0013/dldt/person-detection-retail-0013.xml engine: CPU label: to/be/set/xxx.labels batch: 1 confidence_threshold: 0.5 enable_roi_constraint: true # set enable_roi_constraint to false if you don't want to make the inferred ROI (region of interest) constrained into the camera frame - name: PersonReidentification - model: /home/intel/code/open_model_zoo/model_downloader/Retail/object_reidentification/pedestrian/rmnet_based/0076/dldt/person-reidentification-retail-0076.xml + model:/opt/intel/computer_vision_sdk/deployment_tools/model_downloader/Retail/object_reidentification/pedestrian/rmnet_based/0076/dldt/person-reidentification-retail-0076.xml engine: CPU label: to/be/set/xxx.labels batch: 1 confidence_threshold: 0.7 - outputs: [ImageWindow, RViz, RosTopic] + outputs: [ImageWindow, RosTopic] connects: - - left: RealSenseCamera + - left: StandardCamera right: [ObjectDetection] - left: ObjectDetection right: [PersonReidentification] - left: PersonReidentification - right: [ImageWindow, RViz, RosTopic] + right: [ImageWindow, RosTopic] OpenvinoCommon: \ No newline at end of file diff --git a/vino_launch/param/pipeline_reidentification_oss.yaml b/vino_launch/param/pipeline_reidentification_oss.yaml new file mode 100644 index 00000000..e3f03c09 --- /dev/null +++ b/vino_launch/param/pipeline_reidentification_oss.yaml @@ -0,0 +1,27 @@ +Pipelines: +- name: object + inputs: [StandardCamera] + infers: + - name: ObjectDetection + model: /opt/openvino_toolkit/open_model_zoo/model_downloader/Retail/object_detection/pedestrian/rmnet_ssd/0013/dldt/person-detection-retail-0013.xml + engine: CPU + label: to/be/set/xxx.labels + batch: 1 + confidence_threshold: 0.5 + enable_roi_constraint: true # set enable_roi_constraint to false if you don't want to make the inferred ROI (region of interest) constrained into the camera frame + - name: PersonReidentification + model: /opt/openvino_toolkit/open_model_zoo/model_downloader/Retail/object_reidentification/pedestrian/rmnet_based/0076/dldt/person-reidentification-retail-0076.xml + engine: CPU + label: to/be/set/xxx.labels + batch: 1 + confidence_threshold: 0.7 + outputs: [ImageWindow, RosTopic] + connects: + - left: StandardCamera + right: [ObjectDetection] + - left: ObjectDetection + right: [PersonReidentification] + - left: PersonReidentification + right: [ImageWindow, RosTopic] + +OpenvinoCommon: \ No newline at end of file diff --git a/vino_launch/param/pipeline_segmentation.yaml b/vino_launch/param/pipeline_segmentation.yaml index a5540346..439c1e99 100644 --- a/vino_launch/param/pipeline_segmentation.yaml +++ b/vino_launch/param/pipeline_segmentation.yaml @@ -1,19 +1,19 @@ Pipelines: - name: segmentation - inputs: [RealSenseCamera] + inputs: [RealSenseCameraTopic] infers: - name: ObjectSegmentation model: /opt/models/mask_rcnn_inception_v2_coco_2018_01_28/output/frozen_inference_graph.xml engine: CPU label: to/be/set/xxx.labels batch: 1 - outputs: [ImageWindow] + outputs: [ImageWindow, RosTopic] confidence_threshold: 0.2 connects: - - left: RealSenseCamera + - left: RealSenseCameraTopic right: [ObjectSegmentation] - left: ObjectSegmentation - right: [ImageWindow] + right: [ImageWindow, RosTopic] OpenvinoCommon: diff --git a/vino_launch/param/pipeline_video.yaml b/vino_launch/param/pipeline_video.yaml new file mode 100644 index 00000000..a4c6f2c7 --- /dev/null +++ b/vino_launch/param/pipeline_video.yaml @@ -0,0 +1,20 @@ +Pipelines: +- name: segmentation + inputs: [Video] + input_path: /home/iei/Videos/object_segmentation.MP4 + infers: + - name: ObjectSegmentation + model: /opt/models/mask_rcnn_inception_v2_coco_2018_01_28/output/frozen_inference_graph.xml + engine: CPU + label: to/be/set/xxx.labels + batch: 1 + outputs: [ImageWindow, RosTopic] + confidence_threshold: 0.2 + connects: + - left: Video + right: [ObjectSegmentation] + - left: ObjectSegmentation + right: [ImageWindow, RosTopic] + +OpenvinoCommon: + From 0952e34b12861d4421b01b99512b709ca3ff9d10 Mon Sep 17 00:00:00 2001 From: luyang00 <393780933@qq.com> Date: Fri, 29 Mar 2019 16:25:43 +0800 Subject: [PATCH 07/15] add service support for reid and segmentation --- .../dynamic_vino_lib/outputs/base_output.h | 4 + .../outputs/ros_service_output.h | 9 +- .../services/frame_processing_server.h | 2 + .../src/outputs/ros_service_output.cpp | 19 ++++ .../src/outputs/ros_topic_output.cpp | 9 ++ .../src/services/frame_processing_server.cpp | 12 ++- people_msgs/CMakeLists.txt | 2 + people_msgs/srv/ObjectsInMasksSrv.srv | 19 ++++ people_msgs/srv/ReidentificationSrv.srv | 17 ++++ sample/CMakeLists.txt | 79 +++++++++++++++ sample/src/image_reidentification_client.cpp | 71 +++++++++++++ sample/src/image_reidentification_server.cpp | 99 +++++++++++++++++++ sample/src/image_segmentation_client.cpp | 72 ++++++++++++++ sample/src/image_segmentation_server.cpp | 99 +++++++++++++++++++ .../image_reidentification_server_oss.launch | 9 ++ .../launch/image_segmentation_server.launch | 9 ++ .../param/image_segmentation_server.yaml | 19 ++++ .../pipeline_reidentification_server_oss.yaml | 28 ++++++ 18 files changed, 572 insertions(+), 6 deletions(-) create mode 100644 people_msgs/srv/ObjectsInMasksSrv.srv create mode 100644 people_msgs/srv/ReidentificationSrv.srv create mode 100644 sample/src/image_reidentification_client.cpp create mode 100644 sample/src/image_reidentification_server.cpp create mode 100644 sample/src/image_segmentation_client.cpp create mode 100644 sample/src/image_segmentation_server.cpp create mode 100644 vino_launch/launch/image_reidentification_server_oss.launch create mode 100644 vino_launch/launch/image_segmentation_server.launch create mode 100644 vino_launch/param/image_segmentation_server.yaml create mode 100644 vino_launch/param/pipeline_reidentification_server_oss.yaml diff --git a/dynamic_vino_lib/include/dynamic_vino_lib/outputs/base_output.h b/dynamic_vino_lib/include/dynamic_vino_lib/outputs/base_output.h index 50e66767..13591a50 100644 --- a/dynamic_vino_lib/include/dynamic_vino_lib/outputs/base_output.h +++ b/dynamic_vino_lib/include/dynamic_vino_lib/outputs/base_output.h @@ -126,6 +126,10 @@ class BaseOutput boost::shared_ptr response) {} virtual void setServiceResponse( boost::shared_ptr response) {} + virtual void setServiceResponse( + boost::shared_ptr response) {} + virtual void setServiceResponse( + boost::shared_ptr response) {} Pipeline* getPipeline() const; cv::Mat getFrame() const; virtual void clearData() {} diff --git a/dynamic_vino_lib/include/dynamic_vino_lib/outputs/ros_service_output.h b/dynamic_vino_lib/include/dynamic_vino_lib/outputs/ros_service_output.h index c0cffb74..3ce30e74 100644 --- a/dynamic_vino_lib/include/dynamic_vino_lib/outputs/ros_service_output.h +++ b/dynamic_vino_lib/include/dynamic_vino_lib/outputs/ros_service_output.h @@ -29,13 +29,18 @@ #include #include #include +#include +#include +#include +#include #include #include #include #include #include - +#include +#include #include @@ -71,6 +76,8 @@ class RosServiceOutput : public RosTopicOutput void setServiceResponse(boost::shared_ptr response); void setServiceResponse(boost::shared_ptr response); void setServiceResponse(boost::shared_ptr response); + void setServiceResponse(boost::shared_ptr response); + void setServiceResponse(boost::shared_ptr response); private: const std::string service_name_; diff --git a/dynamic_vino_lib/include/dynamic_vino_lib/services/frame_processing_server.h b/dynamic_vino_lib/include/dynamic_vino_lib/services/frame_processing_server.h index 562a41bd..0284a47c 100644 --- a/dynamic_vino_lib/include/dynamic_vino_lib/services/frame_processing_server.h +++ b/dynamic_vino_lib/include/dynamic_vino_lib/services/frame_processing_server.h @@ -29,6 +29,8 @@ #include #include #include +#include +#include #include #include diff --git a/dynamic_vino_lib/src/outputs/ros_service_output.cpp b/dynamic_vino_lib/src/outputs/ros_service_output.cpp index 4bed2cfc..06a88e2a 100644 --- a/dynamic_vino_lib/src/outputs/ros_service_output.cpp +++ b/dynamic_vino_lib/src/outputs/ros_service_output.cpp @@ -68,6 +68,23 @@ void Outputs::RosServiceOutput::setServiceResponse( } } +void Outputs::RosServiceOutput::setServiceResponse( + boost::shared_ptr response) + { + slog::info << "in ObjectsInMasks service::Response ..."; + if (segmented_object_msg_ptr_ != nullptr) { + response->segmentation.objects_vector = segmented_object_msg_ptr_->objects_vector; + } + } +void Outputs::RosServiceOutput::setServiceResponse( + boost::shared_ptr response) + { + slog::info << "in Reidentification service::Response ..."; + if (person_reid_msg_ptr_ != nullptr) { + response->reidentification.reidentified_vector = person_reid_msg_ptr_->reidentified_vector; + } + } + void Outputs::RosServiceOutput::setServiceResponse( boost::shared_ptr response) { @@ -101,4 +118,6 @@ void Outputs::RosServiceOutput::clearData() age_gender_msg_ptr_ = nullptr; emotions_msg_ptr_ = nullptr; headpose_msg_ptr_ = nullptr; + segmented_object_msg_ptr_ = nullptr; + person_reid_msg_ptr_ = nullptr; } diff --git a/dynamic_vino_lib/src/outputs/ros_topic_output.cpp b/dynamic_vino_lib/src/outputs/ros_topic_output.cpp index 04496148..fb344438 100644 --- a/dynamic_vino_lib/src/outputs/ros_topic_output.cpp +++ b/dynamic_vino_lib/src/outputs/ros_topic_output.cpp @@ -261,6 +261,15 @@ void Outputs::RosTopicOutput::handleOutput() object_msg.header = header; object_msg.objects_vector.swap(object_msg_ptr_->objects_vector); + pub_object_.publish(object_msg); + object_msg_ptr_ = nullptr; + } + if (object_msg_ptr_ != nullptr) + { + object_msgs::ObjectsInBoxes object_msg; + object_msg.header = header; + object_msg.objects_vector.swap(object_msg_ptr_->objects_vector); + pub_object_.publish(object_msg); object_msg_ptr_ = nullptr; } diff --git a/dynamic_vino_lib/src/services/frame_processing_server.cpp b/dynamic_vino_lib/src/services/frame_processing_server.cpp index c4075da2..baaaae67 100644 --- a/dynamic_vino_lib/src/services/frame_processing_server.cpp +++ b/dynamic_vino_lib/src/services/frame_processing_server.cpp @@ -14,6 +14,8 @@ #include "dynamic_vino_lib/services/frame_processing_server.h" #include +#include +#include #include #include #include @@ -48,6 +50,7 @@ void FrameProcessingServer::initService( { Params::ParamManager::getInstance().parse(config_path); Params::ParamManager::getInstance().print(); + auto pcommon = Params::ParamManager::getInstance().getCommon(); auto pipelines = Params::ParamManager::getInstance().getPipelines(); @@ -75,14 +78,13 @@ bool FrameProcessingServer::cbService( for (auto it = pipelines_.begin(); it != pipelines_.end(); ++it) { PipelineManager::PipelineData & p = pipelines_[it->second.params.name.c_str()]; auto input = p.pipeline->getInputDevice(); - + p.pipeline->runOnce(); auto output_handle = p.pipeline->getOutputHandle(); for (auto & pair : output_handle) { if (!pair.first.compare(kOutputTpye_RosService)) { pair.second->setServiceResponse(res); - //Ugly implement because of type difine event.getResponse() = *res; pair.second->clearData(); return true; // TODO(weizhi) , return directly, suppose only 1 pipeline dealing with 1 request. @@ -90,11 +92,11 @@ bool FrameProcessingServer::cbService( } } slog::info << "[FrameProcessingServer] Callback finished!" << slog::endl; - + return false; } - - template class FrameProcessingServer; template class FrameProcessingServer; +template class FrameProcessingServer; +template class FrameProcessingServer; } // namespace vino_service diff --git a/people_msgs/CMakeLists.txt b/people_msgs/CMakeLists.txt index bafaa681..fbf650ad 100644 --- a/people_msgs/CMakeLists.txt +++ b/people_msgs/CMakeLists.txt @@ -42,6 +42,8 @@ add_service_files(FILES EmotionSrv.srv HeadPoseSrv.srv PeopleSrv.srv + ReidentificationSrv.srv + ObjectsInMasksSrv.srv ) generate_messages(DEPENDENCIES std_msgs diff --git a/people_msgs/srv/ObjectsInMasksSrv.srv b/people_msgs/srv/ObjectsInMasksSrv.srv new file mode 100644 index 00000000..8e679129 --- /dev/null +++ b/people_msgs/srv/ObjectsInMasksSrv.srv @@ -0,0 +1,19 @@ +# Copyright (c) 2017 Intel Corporation +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +# This message can represent objects detected and their bounding-boxes in a frame + +string image_path # input: an image +--- +ObjectsInMasks segmentation # ObjectInBox array diff --git a/people_msgs/srv/ReidentificationSrv.srv b/people_msgs/srv/ReidentificationSrv.srv new file mode 100644 index 00000000..238d2c2e --- /dev/null +++ b/people_msgs/srv/ReidentificationSrv.srv @@ -0,0 +1,17 @@ +# Copyright (c) 2017 Intel Corporation +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +string image_path # input: an image +--- +ReidentificationStamped reidentification # ObjectInBox array diff --git a/sample/CMakeLists.txt b/sample/CMakeLists.txt index 0e918807..f91efb5c 100644 --- a/sample/CMakeLists.txt +++ b/sample/CMakeLists.txt @@ -194,6 +194,85 @@ target_link_libraries(image_object_client ${OpenCV_LIBRARIES} ) + +add_executable(image_segmentation_client + src/image_segmentation_client.cpp +) + +add_dependencies(image_segmentation_client + ${${PROJECT_NAME}_EXPORTED_TARGETS} + ${catkin_EXPORTED_TARGETS} + ${dynamic_vino_lib_TARGETS} +) + +target_link_libraries(image_segmentation_client + ${catkin_LIBRARIES} + cpu_extension + gflags + ${vino_param_lib_LIBRARIES} + ${InferenceEngine_LIBRARIES} + ${OpenCV_LIBRARIES} +) + +add_executable(image_segmentation_server + src/image_segmentation_server.cpp +) + +add_dependencies(image_segmentation_server + ${${PROJECT_NAME}_EXPORTED_TARGETS} + ${catkin_EXPORTED_TARGETS} + ${dynamic_vino_lib_TARGETS} +) + +target_link_libraries(image_segmentation_server + ${catkin_LIBRARIES} + cpu_extension + gflags + ${vino_param_lib_LIBRARIES} + ${InferenceEngine_LIBRARIES} + ${OpenCV_LIBRARIES} +) + + +add_executable(image_reidentification_client + src/image_reidentification_client.cpp +) + +add_dependencies(image_reidentification_client + ${${PROJECT_NAME}_EXPORTED_TARGETS} + ${catkin_EXPORTED_TARGETS} + ${dynamic_vino_lib_TARGETS} +) + +target_link_libraries(image_reidentification_client + ${catkin_LIBRARIES} + cpu_extension + gflags + ${vino_param_lib_LIBRARIES} + ${InferenceEngine_LIBRARIES} + ${OpenCV_LIBRARIES} +) + +add_executable(image_reidentification_server + src/image_reidentification_server.cpp +) + +add_dependencies(image_reidentification_server + ${${PROJECT_NAME}_EXPORTED_TARGETS} + ${catkin_EXPORTED_TARGETS} + ${dynamic_vino_lib_TARGETS} +) + +target_link_libraries(image_reidentification_server + ${catkin_LIBRARIES} + cpu_extension + gflags + ${vino_param_lib_LIBRARIES} + ${InferenceEngine_LIBRARIES} + ${OpenCV_LIBRARIES} +) + + if(UNIX OR APPLE) # Linker flags. if( ${CMAKE_CXX_COMPILER_ID} STREQUAL "GNU" OR ${CMAKE_CXX_COMPILER_ID} STREQUAL "Intel") diff --git a/sample/src/image_reidentification_client.cpp b/sample/src/image_reidentification_client.cpp new file mode 100644 index 00000000..70a94991 --- /dev/null +++ b/sample/src/image_reidentification_client.cpp @@ -0,0 +1,71 @@ +/* + * Copyright (c) 2018 Intel Corporation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** +* \brief A sample for this library. This sample performs face detection, + * emotions detection, age gender detection and head pose estimation. +* \file sample/main.cpp +*/ + +#include +#include +#include "opencv2/opencv.hpp" + +#include + + + +int main(int argc, char ** argv) +{ + ros::init(argc, argv, "image_reidentification_client"); + + ros::NodeHandle n; + + ros::ServiceClient client = n.serviceClient("/openvino_toolkit/service"); + + + people_msgs::ReidentificationSrv srv; + + if (client.call(srv)) + { + ROS_INFO("Request service success!"); + + for (unsigned int i = 0; i < srv.response.reidentification.reidentified_vector.size(); i++) { + std::stringstream ss; + ss << srv.response.reidentification.reidentified_vector[i].identity ; + ROS_INFO("%d: object: %s", i, + srv.response.reidentification.reidentified_vector[i].identity.c_str()); + + ROS_INFO( + "location: (%d, %d, %d, %d)", + srv.response.reidentification.reidentified_vector[i].roi.x_offset, srv.response.reidentification.reidentified_vector[i].roi.y_offset, + srv.response.reidentification.reidentified_vector[i].roi.width,srv.response.reidentification.reidentified_vector[i].roi.height); + } + + + } + else + { + ROS_ERROR("Failed to request service \"openvino_toolkit/service\" "); return -1; + } + + + + +} + + + \ No newline at end of file diff --git a/sample/src/image_reidentification_server.cpp b/sample/src/image_reidentification_server.cpp new file mode 100644 index 00000000..86293ddb --- /dev/null +++ b/sample/src/image_reidentification_server.cpp @@ -0,0 +1,99 @@ +/* + * Copyright (c) 2018 Intel Corporation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** +* \brief A sample for this library. This sample performs face detection, + * emotions detection, age gender detection and head pose estimation. +* \file sample/main.cpp +*/ + +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include "dynamic_vino_lib/common.h" +#include "dynamic_vino_lib/engines/engine.h" +#include "dynamic_vino_lib/factory.h" +#include "dynamic_vino_lib/inferences/age_gender_detection.h" +#include "dynamic_vino_lib/inferences/base_inference.h" +#include "dynamic_vino_lib/inferences/emotions_detection.h" +#include "dynamic_vino_lib/inferences/face_detection.h" +#include "dynamic_vino_lib/inferences/head_pose_detection.h" +#include "dynamic_vino_lib/inputs/realsense_camera_topic.h" +#include "dynamic_vino_lib/outputs/image_window_output.h" +#include "dynamic_vino_lib/outputs/ros_topic_output.h" +#include "dynamic_vino_lib/outputs/rviz_output.h" +#include "dynamic_vino_lib/pipeline.h" +#include "dynamic_vino_lib/pipeline_manager.h" +#include "dynamic_vino_lib/slog.h" +#include "inference_engine.hpp" +#include "opencv2/opencv.hpp" +#include "sample/utility.hpp" +#include + + +bool parseAndCheckCommandLine(int argc, char** argv) +{ + // -----Parsing and validation of input args--------------------------- + gflags::ParseCommandLineNonHelpFlags(&argc, &argv, true); + if (FLAGS_h) + { + showUsageForParam(); + return false; + } + + return true; +} + +int main(int argc, char** argv) +{ + ros::init(argc, argv, "image_segmentation_servier"); + + if (!parseAndCheckCommandLine(argc, argv)) return 0; + + ros::param::param("~param_file", FLAGS_config, "/param/image_segmentation_server.yaml"); + + slog::info << "FLAGS_config=" << FLAGS_config << slog::endl; + + std::string service_name = "/openvino_toolkit/service"; + slog::info << "service name=" << service_name << slog::endl; + // ----- Parsing and validation of input args----------------------- + + + auto node = std::make_shared>(service_name, FLAGS_config); + + slog::info << "Waiting for reid service request..." << slog::endl; + ros::spin(); + slog::info << "--------------End of Excution--------------" << FLAGS_config << slog::endl; + +} diff --git a/sample/src/image_segmentation_client.cpp b/sample/src/image_segmentation_client.cpp new file mode 100644 index 00000000..be98d04a --- /dev/null +++ b/sample/src/image_segmentation_client.cpp @@ -0,0 +1,72 @@ +/* + * Copyright (c) 2018 Intel Corporation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** +* \brief A sample for this library. This sample performs face detection, + * emotions detection, age gender detection and head pose estimation. +* \file sample/main.cpp +*/ + +#include +#include +#include "opencv2/opencv.hpp" + +#include + + + +int main(int argc, char ** argv) +{ + ros::init(argc, argv, "image_segmentation_client"); + + ros::NodeHandle n; + + ros::ServiceClient client = n.serviceClient("/openvino_toolkit/service"); + + + people_msgs::ObjectsInMasksSrv srv; + + if (client.call(srv)) + { + ROS_INFO("Request service success!"); + + for (unsigned int i = 0; i < srv.response.segmentation.objects_vector.size(); i++) { + std::stringstream ss; + ss << srv.response.segmentation.objects_vector[i].object_name << ": " << + srv.response.segmentation.objects_vector[i].probability * 100 << "%"; + ROS_INFO("%d: object: %s", i, + srv.response.segmentation.objects_vector[i].object_name.c_str()); + ROS_INFO( "prob: %f", + srv.response.segmentation.objects_vector[i].probability); + ROS_INFO( + "location: (%d, %d, %d, %d)", + srv.response.segmentation.objects_vector[i].roi.x_offset, srv.response.segmentation.objects_vector[i].roi.y_offset, + srv.response.segmentation.objects_vector[i].roi.width,srv.response.segmentation.objects_vector[i].roi.height); + } + + } + else + { + ROS_ERROR("Failed to request service \"openvino_toolkit/service\" "); return -1; + } + + + + +} + + + \ No newline at end of file diff --git a/sample/src/image_segmentation_server.cpp b/sample/src/image_segmentation_server.cpp new file mode 100644 index 00000000..34288a29 --- /dev/null +++ b/sample/src/image_segmentation_server.cpp @@ -0,0 +1,99 @@ +/* + * Copyright (c) 2018 Intel Corporation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** +* \brief A sample for this library. This sample performs face detection, + * emotions detection, age gender detection and head pose estimation. +* \file sample/main.cpp +*/ + +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include "dynamic_vino_lib/common.h" +#include "dynamic_vino_lib/engines/engine.h" +#include "dynamic_vino_lib/factory.h" +#include "dynamic_vino_lib/inferences/age_gender_detection.h" +#include "dynamic_vino_lib/inferences/base_inference.h" +#include "dynamic_vino_lib/inferences/emotions_detection.h" +#include "dynamic_vino_lib/inferences/face_detection.h" +#include "dynamic_vino_lib/inferences/head_pose_detection.h" +#include "dynamic_vino_lib/inputs/realsense_camera_topic.h" +#include "dynamic_vino_lib/outputs/image_window_output.h" +#include "dynamic_vino_lib/outputs/ros_topic_output.h" +#include "dynamic_vino_lib/outputs/rviz_output.h" +#include "dynamic_vino_lib/pipeline.h" +#include "dynamic_vino_lib/pipeline_manager.h" +#include "dynamic_vino_lib/slog.h" +#include "inference_engine.hpp" +#include "opencv2/opencv.hpp" +#include "sample/utility.hpp" + + + +bool parseAndCheckCommandLine(int argc, char** argv) +{ + // -----Parsing and validation of input args--------------------------- + gflags::ParseCommandLineNonHelpFlags(&argc, &argv, true); + if (FLAGS_h) + { + showUsageForParam(); + return false; + } + + return true; +} + +int main(int argc, char** argv) +{ + ros::init(argc, argv, "image_segmentation_servier"); + + if (!parseAndCheckCommandLine(argc, argv)) return 0; + + ros::param::param("~param_file", FLAGS_config, "/param/image_segmentation_server.yaml"); + + slog::info << "FLAGS_config=" << FLAGS_config << slog::endl; + + std::string service_name = "/openvino_toolkit/service"; + slog::info << "service name=" << service_name << slog::endl; + // ----- Parsing and validation of input args----------------------- + + + auto node = std::make_shared>(service_name, FLAGS_config); + + slog::info << "Waiting for seg service request..." << slog::endl; + ros::spin(); + slog::info << "--------------End of Excution--------------" << FLAGS_config << slog::endl; + +} diff --git a/vino_launch/launch/image_reidentification_server_oss.launch b/vino_launch/launch/image_reidentification_server_oss.launch new file mode 100644 index 00000000..3ea12149 --- /dev/null +++ b/vino_launch/launch/image_reidentification_server_oss.launch @@ -0,0 +1,9 @@ + + + + + + + + diff --git a/vino_launch/launch/image_segmentation_server.launch b/vino_launch/launch/image_segmentation_server.launch new file mode 100644 index 00000000..8d748249 --- /dev/null +++ b/vino_launch/launch/image_segmentation_server.launch @@ -0,0 +1,9 @@ + + + + + + + + diff --git a/vino_launch/param/image_segmentation_server.yaml b/vino_launch/param/image_segmentation_server.yaml new file mode 100644 index 00000000..f0e0c16b --- /dev/null +++ b/vino_launch/param/image_segmentation_server.yaml @@ -0,0 +1,19 @@ +Pipelines: +- name: segmentation + inputs: [Image] + infers: + - name: ObjectSegmentation + model: /opt/models/mask_rcnn_inception_v2_coco_2018_01_28/output/frozen_inference_graph.xml + engine: CPU + label: to/be/set/xxx.labels + batch: 1 + outputs: [RosService] + confidence_threshold: 0.2 + connects: + - left: Image + right: [ObjectSegmentation] + - left: ObjectSegmentation + right: [RosService] + input_path: "/opt/openvino_toolkit/ros_openvino_toolkit/data/images/car.png" +OpenvinoCommon: + diff --git a/vino_launch/param/pipeline_reidentification_server_oss.yaml b/vino_launch/param/pipeline_reidentification_server_oss.yaml new file mode 100644 index 00000000..43f00d13 --- /dev/null +++ b/vino_launch/param/pipeline_reidentification_server_oss.yaml @@ -0,0 +1,28 @@ +Pipelines: +- name: object + inputs: [Image] + infers: + - name: ObjectDetection + model: /opt/openvino_toolkit/open_model_zoo/model_downloader/Retail/object_detection/pedestrian/rmnet_ssd/0013/dldt/person-detection-retail-0013.xml + engine: CPU + label: to/be/set/xxx.labels + batch: 1 + confidence_threshold: 0.5 + enable_roi_constraint: true # set enable_roi_constraint to false if you don't want to make the inferred ROI (region of interest) constrained into the camera frame + - name: PersonReidentification + model: /opt/openvino_toolkit/open_model_zoo/model_downloader/Retail/object_reidentification/pedestrian/rmnet_based/0076/dldt/person-reidentification-retail-0076.xml + engine: CPU + label: to/be/set/xxx.labels + batch: 1 + confidence_threshold: 0.7 + outputs: [RosService] + connects: + - left: Image + right: [ObjectDetection] + - left: ObjectDetection + right: [PersonReidentification] + - left: PersonReidentification + right: [RosService] + input_path: "/opt/openvino_toolkit/ros_openvino_toolkit/data/images/team.jpg" + +OpenvinoCommon: \ No newline at end of file From f7c9f28b8768106d4ba98fd6469839380bfa1a73 Mon Sep 17 00:00:00 2001 From: RachelRen05 Date: Mon, 1 Apr 2019 22:14:52 +0800 Subject: [PATCH 08/15] update project --- README.md | 77 +++++++++++++-- .../object_detection/mobilenet-ssd.labels | 21 ++++ doc/BINARY_VERSION_README.md | 97 ++++++++++++++++--- doc/OPEN_SOURCE_CODE_README.md | 7 ++ dynamic_vino_lib/CMakeLists.txt | 1 + .../inputs/realsense_camera_topic.h | 2 +- .../dynamic_vino_lib/outputs/rviz_output.h | 18 ++++ .../dynamic_vino_lib/pipeline_params.h | 8 +- .../src/inputs/realsense_camera_topic.cpp | 25 ++--- .../src/outputs/ros_topic_output.cpp | 2 +- dynamic_vino_lib/src/outputs/rviz_output.cpp | 10 ++ dynamic_vino_lib/src/pipeline_manager.cpp | 1 + sample/src/image_object_client.cpp | 2 +- sample/src/image_people_client.cpp | 9 +- sample/src/pipeline_with_params.cpp | 10 ++ script/environment_setup.sh | 8 +- script/environment_setup_binary.sh | 10 +- vino_launch/launch/pipeline_image.launch | 12 ++- vino_launch/launch/pipeline_image_oss.launch | 11 ++- vino_launch/launch/pipeline_object.launch | 3 +- vino_launch/launch/pipeline_object_oss.launch | 3 +- .../launch/pipeline_object_oss_topic.launch | 12 ++- .../launch/pipeline_object_topic.launch | 23 +++++ vino_launch/launch/pipeline_people.launch | 13 --- .../launch/pipeline_people_myriad.launch | 17 ++++ vino_launch/launch/pipeline_people_oss.launch | 6 +- ...aunch => pipeline_reidentification.launch} | 7 +- .../pipeline_reidentification_oss.launch | 8 +- .../launch/pipeline_segementation.launch | 8 -- .../launch/pipeline_segmentation.launch | 23 +++++ vino_launch/launch/pipeline_video.launch | 8 +- vino_launch/param/image_object_server.yaml | 2 +- .../param/image_object_server_oss.yaml | 2 +- vino_launch/param/image_people_server.yaml | 34 +++---- .../param/image_people_server_oss.yaml | 26 ++--- vino_launch/param/pipeline_image.yaml | 36 +++---- vino_launch/param/pipeline_image_oss.yaml | 28 +++--- vino_launch/param/pipeline_object.yaml | 8 +- vino_launch/param/pipeline_object_oss.yaml | 2 +- .../param/pipeline_object_oss_topic.yaml | 2 +- ...myriad.yaml => pipeline_object_topic.yaml} | 6 +- ...eople.yaml => pipeline_people_myriad.yaml} | 36 +++---- vino_launch/param/pipeline_people_oss.yaml | 20 ++-- .../param/pipeline_reidentification.yaml | 10 +- .../param/pipeline_reidentification_oss.yaml | 6 +- vino_launch/param/pipeline_segmentation.yaml | 8 +- vino_launch/param/pipeline_video.yaml | 6 +- vino_launch/param/rviz/default.rviz | 32 +++--- 48 files changed, 513 insertions(+), 213 deletions(-) create mode 100644 data/labels/object_detection/mobilenet-ssd.labels create mode 100644 vino_launch/launch/pipeline_object_topic.launch delete mode 100644 vino_launch/launch/pipeline_people.launch create mode 100644 vino_launch/launch/pipeline_people_myriad.launch rename vino_launch/launch/{pipeline_object_myriad.launch => pipeline_reidentification.launch} (59%) delete mode 100644 vino_launch/launch/pipeline_segementation.launch create mode 100644 vino_launch/launch/pipeline_segmentation.launch rename vino_launch/param/{pipeline_object_myriad.yaml => pipeline_object_topic.yaml} (65%) rename vino_launch/param/{pipeline_people.yaml => pipeline_people_myriad.yaml} (53%) diff --git a/README.md b/README.md index 63e1728b..2abceb8b 100644 --- a/README.md +++ b/README.md @@ -64,7 +64,7 @@ Currently, the inference feature list is supported: ### Topic #### Subscribed Topic - Image topic: -```/openvino_toolkit/image_raw```([sensor_msgs::Image](http://docs.ros.org/melodic/api/sensor_msgs/html/msg/Image.html)) +```/camera/color/image_raw```([sensor_msgs::Image](http://docs.ros.org/melodic/api/sensor_msgs/html/msg/Image.html)) #### Published Topic - Face Detection: ```/ros_openvino_toolkit/face_detection```([object_msgs::ObjectsInBoxes](https://github.com/intel/object_msgs/blob/master/msg/ObjectsInBoxes.msg)) @@ -121,6 +121,51 @@ See below pictures for the demo result snapshots. # Installation & Launching **NOTE:** Intel releases 2 different series of OpenVINO Toolkit, we call them as [OpenSource Version](https://github.com/opencv/dldt/) and [Tarball Version](https://software.intel.com/en-us/openvino-toolkit). This guidelie uses OpenSource Version as the installation and launching example. **If you want to use Tarball version, please follow [the guide for Tarball Version](https://github.com/intel/ros_openvino_toolkit/blob/devel/doc/BINARY_VERSION_README.md).** +## Enable Intel® Neural Compute Stick 2 (Intel® NCS 2) under the OpenVINO Open Source version (Optional)
+1. Intel Distribution of OpenVINO toolkit
+ * Download OpenVINO toolkit by following the [guide](https://software.intel.com/en-us/openvino-toolkit/choose-download)
+ ```bash + cd ~/Downloads + wget -c http://registrationcenter-download.intel.com/akdlm/irc_nas/15078/l_openvino_toolkit_p_2018.5.455.tgz + ``` + * Install OpenVINO toolkit by following the [guide](https://software.intel.com/en-us/articles/OpenVINO-Install-Linux)
+ ```bash + cd ~/Downloads + tar -xvf l_openvino_toolkit_p_2018.5.455.tgz + cd l_openvino_toolkit_p_2018.5.455 + # root is required instead of sudo + sudo -E ./install_cv_sdk_dependencies.sh + sudo ./install_GUI.sh + # build sample code under OpenVINO toolkit + source /opt/intel/computer_vision_sdk/bin/setupvars.sh + cd /opt/intel/computer_vision_sdk/deployment_tools/inference_engine/samples/ + mkdir build + cd build + cmake .. + make + ``` + * Configure the Neural Compute Stick USB Driver + ```bash + cd ~/Downloads + cat < 97-usbboot.rules + SUBSYSTEM=="usb", ATTRS{idProduct}=="2150", ATTRS{idVendor}=="03e7", GROUP="users", MODE="0666", ENV{ID_MM_DEVICE_IGNORE}="1" + SUBSYSTEM=="usb", ATTRS{idProduct}=="2485", ATTRS{idVendor}=="03e7", GROUP="users", MODE="0666", ENV{ID_MM_DEVICE_IGNORE}="1" + SUBSYSTEM=="usb", ATTRS{idProduct}=="f63b", ATTRS{idVendor}=="03e7", GROUP="users", MODE="0666", ENV{ID_MM_DEVICE_IGNORE}="1" + EOF + sudo cp 97-usbboot.rules /etc/udev/rules.d/ + sudo udevadm control --reload-rules + sudo udevadm trigger + sudo ldconfig + rm 97-usbboot.rules + ``` + +2. Configure the environment (you can write the configuration to your ~/.basrch file)
+ **Note**: If you used root privileges to install the OpenVINO binary package, it installs the Intel Distribution of OpenVINO toolkit in this directory: */opt/intel/openvino_/* + ```bash + export LD_LIBRARY_PATH=$LD_LIBRARY_PATH:/opt/intel/computer_vision_sdk/deployment_tools/inference_engine/samples/build/intel64/Release/lib + source /opt/intel/computer_vision_sdk/bin/setupvars.sh + ``` + ## Dependencies Installation One-step installation scripts are provided for the dependencies' installation. Please see [the guide](https://github.com/intel/ros_openvino_toolkit/blob/devel/doc/OPEN_SOURCE_CODE_README.md) for details. @@ -141,8 +186,11 @@ One-step installation scripts are provided for the dependencies' installation. P sudo ln -s ~/Downloads/models/mask_rcnn_inception_v2_coco_2018_01_28 /opt/models/ #object detection model cd /opt/openvino_toolkit/open_model_zoo/model_downloader - python3 downloader.py --name ssd300 - sudo python3 /opt/openvino_toolkit/dldt/model-optimizer/mo.py --input_model /opt/openvino_toolkit/open_model_zoo/model_downloader/object_detection/common/ssd/300/caffe/ssd300.caffemodel --output_dir /opt/openvino_toolkit/open_model_zoo/model_downloader/object_detection/common/ssd/300/caffe/output/ + python3 ./downloader.py --name mobilenet-ssd + #FP32 precision model + sudo python3 /opt/openvino_toolkit/dldt/model-optimizer/mo.py --input_model /opt/openvino_toolkit/open_model_zoo/model_downloader/object_detection/common/mobilenet-ssd/caffe/mobilenet-ssd.caffemodel --output_dir /opt/openvino_toolkit/open_model_zoo/model_downloader/object_detection/common/mobilenet-ssd/caffe/output/FP32 --mean_values [127.5,127.5,127.5] --scale_values [127.5] + #FP16 precision model + sudo python3 /opt/openvino_toolkit/dldt/model-optimizer/mo.py --input_model /opt/openvino_toolkit/open_model_zoo/model_downloader/object_detection/common/mobilenet-ssd/caffe/mobilenet-ssd.caffemodel --output_dir /opt/openvino_toolkit/open_model_zoo/model_downloader/object_detection/common/mobilenet-ssd/caffe/output/FP16 --data_type=FP16 --mean_values [127.5,127.5,127.5] --scale_values [127.5] * download the optimized Intermediate Representation (IR) of model (excute _once_)
```bash cd /opt/openvino_toolkit/open_model_zoo/model_downloader @@ -150,13 +198,16 @@ One-step installation scripts are provided for the dependencies' installation. P python3 downloader.py --name age-gender-recognition-retail-0013 python3 downloader.py --name emotions-recognition-retail-0003 python3 downloader.py --name head-pose-estimation-adas-0001 + python3 downloader.py --name person-detection-retail-0013 + python3 downloader.py --name person-reidentification-retail-0076 ``` * copy label files (excute _once_)
```bash sudo cp /opt/openvino_toolkit/ros_openvino_toolkit/data/labels/emotions-recognition/FP32/emotions-recognition-retail-0003.labels /opt/openvino_toolkit/open_model_zoo/model_downloader/Retail/object_attributes/emotions_recognition/0003/dldt sudo cp /opt/openvino_toolkit/ros_openvino_toolkit/data/labels/face_detection/face-detection-adas-0001.labels /opt/openvino_toolkit/open_model_zoo/model_downloader/Transportation/object_detection/face/pruned_mobilenet_reduced_ssd_shared_weights/dldt sudo cp /opt/openvino_toolkit/ros_openvino_toolkit/data/labels/object_segmentation/frozen_inference_graph.labels /opt/models/mask_rcnn_inception_v2_coco_2018_01_28/output - sudo cp /opt/openvino_toolkit/ros_openvino_toolkit/data/labels/object_detection/ssd300.labels /opt/openvino_toolkit/open_model_zoo/model_downloader/object_detection/common/ssd/300/caffe/output + sudo cp /opt/openvino_toolkit/ros_openvino_toolkit/data/labels/object_detection/mobilenet-ssd.labels /opt/openvino_toolkit/open_model_zoo/model_downloader/object_detection/common/mobilenet-ssd/caffe/output/FP32 + sudo cp /opt/openvino_toolkit/ros_openvino_toolkit/data/labels/object_detection/mobilenet-ssd.labels /opt/openvino_toolkit/open_model_zoo/model_downloader/object_detection/common/mobilenet-ssd/caffe/output/FP16 ``` * set ENV LD_LIBRARY_PATH
```bash @@ -166,12 +217,19 @@ One-step installation scripts are provided for the dependencies' installation. P ```bash roslaunch vino_launch pipeline_people_oss.launch ``` - -* run object detection sample code input from RealsensCamera.(connect Intel® Neural Compute Stick 2) + +* run face detection sample code input from Image. ```bash - roslaunch vino_launch pipeline_object_myriad.launch + roslaunch vino_launch pipeline_image_oss.launch + ``` +* run object detection sample code input from RealsensCamera. + ```bash + roslaunch vino_launch pipeline_object_oss.launch + ``` +* run object detection sample code input from RealsensCameraTopic. + ```bash + roslaunch vino_launch pipeline_object_oss_topic.launch ``` - * run object segmentation sample code input from RealSenseCameraTopic. ```bash roslaunch vino_launch pipeline_segmentation.launch @@ -200,7 +258,7 @@ One-step installation scripts are provided for the dependencies' installation. P ``` Run example application with an absolute path of an image on another console: ```bash - rosrun dynamic_vino_sample image_people_client + rosrun dynamic_vino_sample image_people_client ~/catkin_ws/src/ros_openvino_toolkit/data/images/team.jpg ``` # TODO Features * Support **result filtering** for inference process, so that the inference results can be filtered to different subsidiary inference. For example, given an image, firstly we do Object Detection on it, secondly we pass cars to vehicle brand recognition and pass license plate to license number recognition. @@ -210,3 +268,4 @@ One-step installation scripts are provided for the dependencies' installation. P # More Information * ros OpenVINO discription writen in Chinese: https://mp.weixin.qq.com/s/BgG3RGauv5pmHzV_hkVAdw + diff --git a/data/labels/object_detection/mobilenet-ssd.labels b/data/labels/object_detection/mobilenet-ssd.labels new file mode 100644 index 00000000..87df23ce --- /dev/null +++ b/data/labels/object_detection/mobilenet-ssd.labels @@ -0,0 +1,21 @@ +background +aeroplane +bicycle +bird +boat +bottle +bus +car +cat +chair +cow +diningtable +dog +horse +motorbike +person +pottedplant +sheep +sofa +train +tvmonitor diff --git a/doc/BINARY_VERSION_README.md b/doc/BINARY_VERSION_README.md index a5aa85ce..6891fd07 100644 --- a/doc/BINARY_VERSION_README.md +++ b/doc/BINARY_VERSION_README.md @@ -110,11 +110,17 @@ cd ~/catkin_ws/src git clone https://github.com/intel/ros_openvino_toolkit git clone https://github.com/intel/object_msgs git clone https://github.com/ros-perception/vision_opencv +git clone https://github.com/intel-ros/realsense +cd realsense +git checkout 2.1.3 ``` - Build package ``` +# Ubuntu 16.04 source /opt/ros/kinetic/setup.bash +# Ubuntu 18.04 +source /opt/ros/melodic/setup.bash source /opt/intel/computer_vision_sdk/bin/setupvars.sh export OpenCV_DIR=$HOME/code/opencv/build cd ~/catkin_ws @@ -128,33 +134,96 @@ sudo ln -s ~/catkin_ws/src/ros_openvino_toolkit /opt/openvino_toolkit/ros_openvi * Preparation * download and convert a trained model to produce an optimized Intermediate Representation (IR) of the model ```bash - cd /opt/intel/computer_vision_sdk/deployment_tools/model_optimizer/install_prerequisites - sudo ./install_prerequisites.sh - #object detection model - cd /opt/intel/computer_vision_sdk/deployment_tools/model_downloader - sudo python3 downloader.py --name ssd300 - sudo python3 /opt/intel/computer_vision_sdk/deployment_tools/model_optimizer/mo.py --input_model /opt/intel/computer_vision_sdk/deployment_tools/model_downloader/object_detection/common/ssd/300/caffe/ssd300.caffemodel --output_dir /opt/intel/computer_vision_sdk/deployment_tools/model_downloader/object_detection/common/ssd/300/caffe/output/ - ``` + #object segmentation model + cd /opt/intel/computer_vision_sdk/deployment_tools/model_optimizer/install_prerequisites + sudo ./install_prerequisites.sh + mkdir -p ~/Downloads/models + cd ~/Downloads/models + wget http://download.tensorflow.org/models/object_detection/mask_rcnn_inception_v2_coco_2018_01_28.tar.gz + tar -zxvf mask_rcnn_inception_v2_coco_2018_01_28.tar.gz + cd mask_rcnn_inception_v2_coco_2018_01_28 + python3 /opt/intel/computer_vision_sdk/deployment_tools/model_optimizer/mo_tf.py --input_model frozen_inference_graph.pb --tensorflow_use_custom_operations_config /opt/intel/computer_vision_sdk/deployment_tools/model_optimizer/extensions/front/tf/mask_rcnn_support.json --tensorflow_object_detection_api_pipeline_config pipeline.config --reverse_input_channels --output_dir ./output/ + sudo mkdir -p /opt/models + sudo ln -sf ~/Downloads/models/mask_rcnn_inception_v2_coco_2018_01_28 /opt/models/ + #object detection model + cd /opt/intel/computer_vision_sdk/deployment_tools/model_downloader + sudo python3 ./downloader.py --name mobilenet-ssd + #FP32 precision model + sudo python3 /opt/intel/computer_vision_sdk/deployment_tools/model_optimizer/mo.py --input_model /opt/intel/computer_vision_sdk/deployment_tools/model_downloader/object_detection/common/mobilenet-ssd/caffe/mobilenet-ssd.caffemodel --output_dir /opt/intel/computer_vision_sdk/deployment_tools/model_downloader/object_detection/common/mobilenet-ssd/caffe/output/FP32 --mean_values [127.5,127.5,127.5] --scale_values [127.5] + #FP16 precision model + sudo python3 /opt/intel/computer_vision_sdk/deployment_tools/model_optimizer/mo.py --input_model /opt/intel/computer_vision_sdk/deployment_tools/model_downloader/object_detection/common/mobilenet-ssd/caffe/mobilenet-ssd.caffemodel --output_dir /opt/intel/computer_vision_sdk/deployment_tools/model_downloader/object_detection/common/mobilenet-ssd/caffe/output/FP16 --data_type=FP16 --mean_values [127.5,127.5,127.5] --scale_values [127.5] + ``` * copy label files (excute _once_)
```bash sudo cp /opt/openvino_toolkit/ros_openvino_toolkit/data/labels/emotions-recognition/FP32/emotions-recognition-retail-0003.labels /opt/intel/computer_vision_sdk/deployment_tools/intel_models/emotions-recognition-retail-0003/FP32 + sudo cp /opt/openvino_toolkit/ros_openvino_toolkit/data/labels/emotions-recognition/FP32/emotions-recognition-retail-0003.labels /opt/intel/computer_vision_sdk/deployment_tools/intel_models/emotions-recognition-retail-0003/FP16 sudo cp /opt/openvino_toolkit/ros_openvino_toolkit/data/labels/face_detection/face-detection-adas-0001.labels /opt/intel/computer_vision_sdk/deployment_tools/intel_models/face-detection-adas-0001/FP32 - sudo cp /opt/openvino_toolkit/ros_openvino_toolkit/data/labels/object_detection/ssd300.labels /opt/intel/computer_vision_sdk/deployment_tools/model_downloader/object_detection/common/ssd/300/caffe/output + sudo cp /opt/openvino_toolkit/ros_openvino_toolkit/data/labels/face_detection/face-detection-adas-0001.labels /opt/intel/computer_vision_sdk/deployment_tools/intel_models/face-detection-adas-0001/FP16 + sudo cp /opt/openvino_toolkit/ros_openvino_toolkit/data/labels/object_segmentation/frozen_inference_graph.labels ~/Downloads/models/mask_rcnn_inception_v2_coco_2018_01_28/output + sudo cp /opt/openvino_toolkit/ros_openvino_toolkit/data/labels/object_detection/mobilenet-ssd.labels /opt/intel/computer_vision_sdk/deployment_tools/model_downloader/object_detection/common/mobilenet-ssd/caffe/output/FP32 + sudo cp /opt/openvino_toolkit/ros_openvino_toolkit/data/labels/object_detection/mobilenet-ssd.labels /opt/intel/computer_vision_sdk/deployment_tools/model_downloader/object_detection/common/mobilenet-ssd/caffe/output/FP16 ``` - * set ENV LD_LIBRARY_PATH + * set ENV LD_LIBRARY_PATH and environment ```bash + source /opt/intel/computer_vision_sdk/bin/setupvars.sh export LD_LIBRARY_PATH=$LD_LIBRARY_PATH:/opt/intel/computer_vision_sdk/deployment_tools/inference_engine/samples/build/intel64/Release/lib ``` -* run face detection sample code input from StandardCamera. +* run face detection sample code input from StandardCamera.(connect Intel® Neural Compute Stick 2) + ```bash + roslaunch vino_launch pipeline_people_myriad.launch + ``` +* run face detection sample code input from Image. ```bash - roslaunch vino_launch pipeline_people.launch + roslaunch vino_launch pipeline_image.launch ``` -* run object detection sample code input from RealsensCamera. +* run object detection sample code input from RealSenseCamera.(connect Intel® Neural Compute Stick 2) ```bash roslaunch vino_launch pipeline_object.launch ``` +* run object detection sample code input from RealSenseCameraTopic.(connect Intel® Neural Compute Stick 2) + ```bash + roslaunch vino_launch pipeline_object_topic.launch + ``` +* run object segmentation sample code input from RealSenseCameraTopic.(connect Intel® Neural Compute Stick 2) + ```bash + roslaunch vino_launch pipeline_segmentation.launch + ``` +* run object segmentation sample code input from Video. + ```bash + roslaunch vino_launch pipeline_video.launch + ``` +* run person reidentification sample code input from StandardCamera. + ```bash + roslaunch vino_launch pipeline_reidentification.launch + ``` +* run object detection service sample code input from Image + Run image processing service: + ```bash + roslaunch vino_launch image_object_server.launch + ``` + Run example application with an absolute path of an image on another console: + ```bash + rosrun dynamic_vino_sample image_object_client ~/catkin_ws/src/ros_openvino_toolkit/data/images/car.png + ``` +* run people detection service sample code input from Image + Run image processing service: + ```bash + roslaunch vino_launch image_people_server.launch + ``` + Run example application with an absolute path of an image on another console: + ```bash + rosrun dynamic_vino_sample image_people_client ~/catkin_ws/src/ros_openvino_toolkit/data/images/team.jpg + ``` ## 6. Known Issues -- Video and image detection support is going to be verified. -- Segmentation fault occurs occasionally, which is caused by librealsense library. See [Issue #2645](https://github.com/IntelRealSense/librealsense/issues/2645) for more details. +* Possible problems + * When running sample with Intel® Neural Compute Stick 2 occurred error: + ```bash + E: [ncAPI] [ 0] ncDeviceOpen:668 failed to find device + # or + E: [ncAPI] [ 0] ncDeviceCreate:324 global mutex initialization failed + ``` + > solution - Please refer to the [guide](https://software.intel.com/en-us/neural-compute-stick/get-started) to set up the environment. + * Segmentation fault occurs occasionally, which is caused by librealsense library. See [Issue #2645](https://github.com/IntelRealSense/librealsense/issues/2645) for more details. ###### *Any security issue should be reported using process at https://01.org/security* + diff --git a/doc/OPEN_SOURCE_CODE_README.md b/doc/OPEN_SOURCE_CODE_README.md index 806a0641..adc94e0c 100644 --- a/doc/OPEN_SOURCE_CODE_README.md +++ b/doc/OPEN_SOURCE_CODE_README.md @@ -130,15 +130,22 @@ This project is a ROS wrapper for CV API of [OpenVINO™](https://software.intel git clone https://github.com/intel/ros_openvino_toolkit git clone https://github.com/intel/object_msgs git clone https://github.com/ros-perception/vision_opencv + git clone https://github.com/intel-ros/realsense + cd realsense + git checkout 2.1.3 ``` * Build package **Note**:Please modify kinetic to melodic if you are Ubuntu 18.04 user ``` + # Ubuntu 16.04 source /opt/ros/kinetic/setup.bash + # Ubuntu 18.04 + source /opt/ros/melodic/setup.bash cd ~/catkin_ws catkin_make source devel/setup.bash sudo mkdir -p /opt/openvino_toolkit sudo ln -s ~/catkin_ws/src/ros_openvino_toolkit /opt/openvino_toolkit/ros_openvino_toolkit ``` + diff --git a/dynamic_vino_lib/CMakeLists.txt b/dynamic_vino_lib/CMakeLists.txt index b9fae78d..86c0679f 100644 --- a/dynamic_vino_lib/CMakeLists.txt +++ b/dynamic_vino_lib/CMakeLists.txt @@ -170,6 +170,7 @@ add_library(${PROJECT_NAME} SHARED add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS} + "object_msgs" ) target_link_libraries(${PROJECT_NAME} diff --git a/dynamic_vino_lib/include/dynamic_vino_lib/inputs/realsense_camera_topic.h b/dynamic_vino_lib/include/dynamic_vino_lib/inputs/realsense_camera_topic.h index 9f92a5b4..8d5fbf9d 100644 --- a/dynamic_vino_lib/include/dynamic_vino_lib/inputs/realsense_camera_topic.h +++ b/dynamic_vino_lib/include/dynamic_vino_lib/inputs/realsense_camera_topic.h @@ -58,7 +58,7 @@ class RealSenseCameraTopic : public BaseInputDevice ros::NodeHandle nh_; image_transport::Subscriber sub_; cv::Mat image; - int image_count; + cv::Mat last_image; void cb(const sensor_msgs::ImageConstPtr& image_msg); }; diff --git a/dynamic_vino_lib/include/dynamic_vino_lib/outputs/rviz_output.h b/dynamic_vino_lib/include/dynamic_vino_lib/outputs/rviz_output.h index 0de428a4..595e1864 100644 --- a/dynamic_vino_lib/include/dynamic_vino_lib/outputs/rviz_output.h +++ b/dynamic_vino_lib/include/dynamic_vino_lib/outputs/rviz_output.h @@ -80,6 +80,24 @@ class RvizOutput : public BaseOutput */ void accept(const std::vector &) override; + /** + * @brief Generate rviz output content according to + * the object segmentation result. + * @param[in] An object segmentation result objetc. + */ + void accept(const std::vector&) override; + /** + * @brief Generate rviz output content according to + * the person re-ID result. + * @param[in] An object segmentation result objetc. + */ + void accept(const std::vector &) override; + /** + * @brief Merge mask for image window ouput + * the object segmentation result. + * @param[in] An object segmentation result objetc. + */ + private: std_msgs::Header getHeader(); ros::NodeHandle nh_; diff --git a/dynamic_vino_lib/include/dynamic_vino_lib/pipeline_params.h b/dynamic_vino_lib/include/dynamic_vino_lib/pipeline_params.h index ec9dc36f..4344a48c 100644 --- a/dynamic_vino_lib/include/dynamic_vino_lib/pipeline_params.h +++ b/dynamic_vino_lib/include/dynamic_vino_lib/pipeline_params.h @@ -48,10 +48,10 @@ const char kOutputTpye_ImageWindow[] = "ImageWindow"; const char kOutputTpye_RosTopic[] = "RosTopic"; const char kOutputTpye_RosService[] = "RosService"; -const char kInferTpye_FaceDetection[] = "face_detection"; -const char kInferTpye_AgeGenderRecognition[] = "age_gender_detection"; -const char kInferTpye_EmotionRecognition[] = "emotion_detection"; -const char kInferTpye_HeadPoseEstimation[] = "head_pose_detection"; +const char kInferTpye_FaceDetection[] = "FaceDetection"; +const char kInferTpye_AgeGenderRecognition[] = "AgeGenderRecognition"; +const char kInferTpye_EmotionRecognition[] = "EmotionRecognition"; +const char kInferTpye_HeadPoseEstimation[] = "HeadPoseEstimation"; const char kInferTpye_ObjectDetection[] = "ObjectDetection"; const char kInferTpye_ObjectSegmentation[] = "ObjectSegmentation"; const char kInferTpye_PersonReidentification[] = "PersonReidentification"; diff --git a/dynamic_vino_lib/src/inputs/realsense_camera_topic.cpp b/dynamic_vino_lib/src/inputs/realsense_camera_topic.cpp index 8528cc87..900ffa07 100644 --- a/dynamic_vino_lib/src/inputs/realsense_camera_topic.cpp +++ b/dynamic_vino_lib/src/inputs/realsense_camera_topic.cpp @@ -34,35 +34,36 @@ Input::RealSenseCameraTopic::RealSenseCameraTopic() bool Input::RealSenseCameraTopic::initialize() { slog::info << "before cameraTOpic init" << slog::endl; - + std::shared_ptr it = - std::make_shared(nh_); + std::make_shared(nh_); sub_ = it->subscribe("/camera/color/image_raw", 1, &RealSenseCameraTopic::cb, - this); - - image_count = 0; + this); return true; } void Input::RealSenseCameraTopic::cb( const sensor_msgs::ImageConstPtr& image_msg) { - slog::info << "Receiving a new image from Camera topic." << slog::endl; image = cv_bridge::toCvCopy(image_msg, "bgr8")->image; - ++image_count; } bool Input::RealSenseCameraTopic::read(cv::Mat* frame) { - if (image.empty() || image_count <= 0) + ros::spinOnce(); + //nothing in topics from begining + if (image.empty() && last_image.empty()) { slog::warn << "No data received in CameraTopic instance" << slog::endl; return false; } - - *frame = image; - --image_count; - + if(image.empty()) { + *frame = last_image; + } + else + { + *frame = image; + } return true; } diff --git a/dynamic_vino_lib/src/outputs/ros_topic_output.cpp b/dynamic_vino_lib/src/outputs/ros_topic_output.cpp index 04496148..4eec6fcb 100644 --- a/dynamic_vino_lib/src/outputs/ros_topic_output.cpp +++ b/dynamic_vino_lib/src/outputs/ros_topic_output.cpp @@ -36,7 +36,7 @@ Outputs::RosTopicOutput::RosTopicOutput() pub_headpose_ = nh_.advertise( "/openvino_toolkit/headposes", 16); pub_object_ = nh_.advertise( - "/openvino_toolkit/objects", 16); + "/openvino_toolkit/detected_objects", 16); pub_person_reid_ = nh_.advertise( "/openvino_toolkit/reidentified_persons", 16); pub_segmented_object_ = nh_.advertise( diff --git a/dynamic_vino_lib/src/outputs/rviz_output.cpp b/dynamic_vino_lib/src/outputs/rviz_output.cpp index ec876c48..64f99b92 100644 --- a/dynamic_vino_lib/src/outputs/rviz_output.cpp +++ b/dynamic_vino_lib/src/outputs/rviz_output.cpp @@ -63,6 +63,16 @@ void Outputs::RvizOutput::accept(const std::vectoraccept(results); } +void Outputs::RvizOutput::accept(const std::vector& results) +{ + image_window_output_->accept(results); +} +void Outputs::RvizOutput::accept(const std::vector & results) +{ + image_window_output_->accept(results); +} + + void Outputs::RvizOutput::handleOutput() { image_window_output_->setPipeline(getPipeline()); diff --git a/dynamic_vino_lib/src/pipeline_manager.cpp b/dynamic_vino_lib/src/pipeline_manager.cpp index 2da27143..0e066d8f 100644 --- a/dynamic_vino_lib/src/pipeline_manager.cpp +++ b/dynamic_vino_lib/src/pipeline_manager.cpp @@ -110,6 +110,7 @@ PipelineManager::parseInputDevice( device = std::make_shared(); } else if (name == kInputType_CameraTopic) { device = std::make_shared(); + std::cout <<"register yaml"<(params.input_meta); diff --git a/sample/src/image_object_client.cpp b/sample/src/image_object_client.cpp index b8bae4bb..3ce85e3a 100644 --- a/sample/src/image_object_client.cpp +++ b/sample/src/image_object_client.cpp @@ -99,4 +99,4 @@ int main(int argc, char ** argv) } - \ No newline at end of file + diff --git a/sample/src/image_people_client.cpp b/sample/src/image_people_client.cpp index ff9f979d..5dfb1b60 100644 --- a/sample/src/image_people_client.cpp +++ b/sample/src/image_people_client.cpp @@ -32,6 +32,13 @@ int main(int argc, char ** argv) ros::init(argc, argv, "image_people_client"); ros::NodeHandle n; + if (argc != 2) { + ROS_INFO( "Usage: rosrun dynamic_vino_sample image_people_client" + ""); + return -1; + } + + ros::ServiceClient client = n.serviceClient("/openvino_toolkit/service"); people_msgs::PeopleSrv srv; @@ -73,4 +80,4 @@ int main(int argc, char ** argv) } - \ No newline at end of file + diff --git a/sample/src/pipeline_with_params.cpp b/sample/src/pipeline_with_params.cpp index 7cfd2798..475d6cb3 100644 --- a/sample/src/pipeline_with_params.cpp +++ b/sample/src/pipeline_with_params.cpp @@ -59,6 +59,13 @@ #include "opencv2/opencv.hpp" #include "sample/utility.hpp" +void signalHandler(int signum) +{ + slog::warn << "!!!!!!!!!!!Interrupt signal (" << signum << ") received!!!!!!!!!!!!" << slog::endl; + + PipelineManager::getInstance().stopAll(); +} + bool parseAndCheckCommandLine(int argc, char** argv) { // -----Parsing and validation of input args--------------------------- @@ -77,6 +84,9 @@ int main(int argc, char** argv) ros::init(argc, argv, "sample_with_params"); + // register signal SIGINT and signal handler + signal(SIGINT, signalHandler); + std::string FLAGS_config; ros::param::param("~param_file", FLAGS_config, "/param/pipeline_people.yaml"); slog::info << "FLAGS_config=" << FLAGS_config << slog::endl; diff --git a/script/environment_setup.sh b/script/environment_setup.sh index 2a943d90..9f6e4574 100755 --- a/script/environment_setup.sh +++ b/script/environment_setup.sh @@ -78,9 +78,9 @@ fi if [ "$ROS_DEBIAN" == "1" ]; then echo "===================Installing ROS from Debian Package...=======================" echo $ROOT_PASSWD | sudo -S sh -c 'echo "deb http://packages.ros.org/ros/ubuntu $(lsb_release -sc) main" > /etc/apt/sources.list.d/ros-latest.list' - echo $ROOT_PASSWD | sudo -S apt-key adv --keyserver hkp://ha.pool.sks-keyservers.net:80 --recv-key 421C365BD9FF1F717815A3895523BAEEB01FA116 + #echo $ROOT_PASSWD | sudo -S apt-key adv --keyserver hkp://ha.pool.sks-keyservers.net:80 --recv-key 421C365BD9FF1F717815A3895523BAEEB01FA116 #For those who cannot access hkp protocal - #echo $ROOT_PASSWD | curl http://repo.ros2.org/repos.key | sudo apt-key add - + echo $ROOT_PASSWD | curl http://repo.ros2.org/repos.key | sudo apt-key add - echo $ROOT_PASSWD | sudo -S apt-get update echo $ROOT_PASSWD | sudo -S apt-get install -y ros-$ros_ver-desktop-full #For ubuntu16.04 Ros-melodic @@ -204,7 +204,7 @@ if [ "$DLDT" == "1" ]; then mkdir -p ~/code && cd ~/code git clone https://github.com/opencv/dldt.git cd dldt/inference-engine/ - git checkout 2018_R4 + git checkout 2018_R5 git submodule init git submodule update --recursive mkdir build && cd build @@ -221,7 +221,7 @@ if [ "$MODEL_ZOO" == "1" ]; then mkdir -p ~/code && cd ~/code git clone https://github.com/opencv/open_model_zoo.git cd open_model_zoo/demos/ - git checkout 2018_R4 + git checkout 2018_R5 mkdir build && cd build cmake -DCMAKE_BUILD_TYPE=Release /opt/openvino_toolkit/dldt/inference-engine make -j8 diff --git a/script/environment_setup_binary.sh b/script/environment_setup_binary.sh index 7f9977d5..7a2adf17 100755 --- a/script/environment_setup_binary.sh +++ b/script/environment_setup_binary.sh @@ -72,9 +72,9 @@ fi if [ "$ROS_DEBIAN" == "1" ]; then echo "===================Installing ROS from Debian Package...=======================" echo $ROOT_PASSWD | sudo -S sh -c 'echo "deb http://packages.ros.org/ros/ubuntu $(lsb_release -sc) main" > /etc/apt/sources.list.d/ros-latest.list' - echo $ROOT_PASSWD | sudo -S apt-key adv --keyserver hkp://ha.pool.sks-keyservers.net:80 --recv-key 421C365BD9FF1F717815A3895523BAEEB01FA116 + #echo $ROOT_PASSWD | sudo -S apt-key adv --keyserver hkp://ha.pool.sks-keyservers.net:80 --recv-key 421C365BD9FF1F717815A3895523BAEEB01FA116 #For those who cannot access hkp protocal - #echo $ROOT_PASSWD | curl http://repo.ros2.org/repos.key | sudo apt-key add - + echo $ROOT_PASSWD | curl http://repo.ros2.org/repos.key | sudo apt-key add - echo $ROOT_PASSWD | sudo -S apt-get update echo $ROOT_PASSWD | sudo -S apt-get install -y ros-$ros_ver-desktop-full @@ -140,9 +140,9 @@ fi #setup OPENVINO if [ "$OPENVINO" == "1" ]; then cd ~/Downloads - wget -c http://registrationcenter-download.intel.com/akdlm/irc_nas/14920/l_openvino_toolkit_p_2018.4.420.tgz - tar -xvf l_openvino_toolkit_p_2018.4.420.tgz - cd l_openvino_toolkit_p_2018.4.420 + wget -c http://registrationcenter-download.intel.com/akdlm/irc_nas/15078/l_openvino_toolkit_p_2018.5.455.tgz + tar -xvf l_openvino_toolkit_p_2018.5.455.tgz + cd l_openvino_toolkit_p_2018.5.455 echo $ROOT_PASSWD | sudo -S ./install_cv_sdk_dependencies.sh cp $basedir/openvino_silent.cfg . echo $ROOT_PASSWD | sudo -S ./install.sh --silent openvino_silent.cfg diff --git a/vino_launch/launch/pipeline_image.launch b/vino_launch/launch/pipeline_image.launch index 162c50c1..ac037862 100644 --- a/vino_launch/launch/pipeline_image.launch +++ b/vino_launch/launch/pipeline_image.launch @@ -1,8 +1,18 @@ + + - + + + + + + + + + diff --git a/vino_launch/launch/pipeline_image_oss.launch b/vino_launch/launch/pipeline_image_oss.launch index c9187e4f..04d43e8f 100644 --- a/vino_launch/launch/pipeline_image_oss.launch +++ b/vino_launch/launch/pipeline_image_oss.launch @@ -1,8 +1,17 @@ + - + + + + + + + + + diff --git a/vino_launch/launch/pipeline_object.launch b/vino_launch/launch/pipeline_object.launch index 1896d6ea..021ed11b 100644 --- a/vino_launch/launch/pipeline_object.launch +++ b/vino_launch/launch/pipeline_object.launch @@ -5,7 +5,8 @@ - + + diff --git a/vino_launch/launch/pipeline_object_oss.launch b/vino_launch/launch/pipeline_object_oss.launch index d1b6d4c7..8f450044 100644 --- a/vino_launch/launch/pipeline_object_oss.launch +++ b/vino_launch/launch/pipeline_object_oss.launch @@ -5,7 +5,8 @@ - + + diff --git a/vino_launch/launch/pipeline_object_oss_topic.launch b/vino_launch/launch/pipeline_object_oss_topic.launch index dfe85513..5624dfea 100644 --- a/vino_launch/launch/pipeline_object_oss_topic.launch +++ b/vino_launch/launch/pipeline_object_oss_topic.launch @@ -2,10 +2,20 @@ + + + + + + + + + - + + diff --git a/vino_launch/launch/pipeline_object_topic.launch b/vino_launch/launch/pipeline_object_topic.launch new file mode 100644 index 00000000..3e2f0e98 --- /dev/null +++ b/vino_launch/launch/pipeline_object_topic.launch @@ -0,0 +1,23 @@ + + + + + + + + + + + + + + + + + + + + + + diff --git a/vino_launch/launch/pipeline_people.launch b/vino_launch/launch/pipeline_people.launch deleted file mode 100644 index c83bf80e..00000000 --- a/vino_launch/launch/pipeline_people.launch +++ /dev/null @@ -1,13 +0,0 @@ - - - - - - - - - - - - diff --git a/vino_launch/launch/pipeline_people_myriad.launch b/vino_launch/launch/pipeline_people_myriad.launch new file mode 100644 index 00000000..2dbc86ca --- /dev/null +++ b/vino_launch/launch/pipeline_people_myriad.launch @@ -0,0 +1,17 @@ + + + + + + + + + + + + + + + + diff --git a/vino_launch/launch/pipeline_people_oss.launch b/vino_launch/launch/pipeline_people_oss.launch index ae0ad38a..0d7a2b13 100644 --- a/vino_launch/launch/pipeline_people_oss.launch +++ b/vino_launch/launch/pipeline_people_oss.launch @@ -5,7 +5,11 @@ - + + + + + diff --git a/vino_launch/launch/pipeline_object_myriad.launch b/vino_launch/launch/pipeline_reidentification.launch similarity index 59% rename from vino_launch/launch/pipeline_object_myriad.launch rename to vino_launch/launch/pipeline_reidentification.launch index 1a27eeb4..5461fcc9 100644 --- a/vino_launch/launch/pipeline_object_myriad.launch +++ b/vino_launch/launch/pipeline_reidentification.launch @@ -1,11 +1,12 @@ - + - - + + + diff --git a/vino_launch/launch/pipeline_reidentification_oss.launch b/vino_launch/launch/pipeline_reidentification_oss.launch index e4ad103c..eaa393e3 100644 --- a/vino_launch/launch/pipeline_reidentification_oss.launch +++ b/vino_launch/launch/pipeline_reidentification_oss.launch @@ -1,8 +1,14 @@ + - + + + + + + diff --git a/vino_launch/launch/pipeline_segementation.launch b/vino_launch/launch/pipeline_segementation.launch deleted file mode 100644 index 2e2f26d9..00000000 --- a/vino_launch/launch/pipeline_segementation.launch +++ /dev/null @@ -1,8 +0,0 @@ - - - - - - - diff --git a/vino_launch/launch/pipeline_segmentation.launch b/vino_launch/launch/pipeline_segmentation.launch new file mode 100644 index 00000000..4a47a9e3 --- /dev/null +++ b/vino_launch/launch/pipeline_segmentation.launch @@ -0,0 +1,23 @@ + + + + + + + + + + + + + + + + + + + + + + diff --git a/vino_launch/launch/pipeline_video.launch b/vino_launch/launch/pipeline_video.launch index 8d48a4ef..f74971b7 100644 --- a/vino_launch/launch/pipeline_video.launch +++ b/vino_launch/launch/pipeline_video.launch @@ -1,8 +1,14 @@ + - + + + + + + diff --git a/vino_launch/param/image_object_server.yaml b/vino_launch/param/image_object_server.yaml index 749157fe..2f9e2f27 100644 --- a/vino_launch/param/image_object_server.yaml +++ b/vino_launch/param/image_object_server.yaml @@ -3,7 +3,7 @@ Pipelines: inputs: [Image] infers: - name: ObjectDetection - model: /opt/intel/computer_vision_sdk/deployment_tools/model_downloader/object_detection/common/ssd/300/caffe/output/ssd300.xml + model: /opt/intel/computer_vision_sdk/deployment_tools/model_downloader/object_detection/common/mobilenet-ssd/caffe/output/FP32/mobilenet-ssd.xml engine: CPU label: to/be/set/xxx.labels batch: 16 diff --git a/vino_launch/param/image_object_server_oss.yaml b/vino_launch/param/image_object_server_oss.yaml index 9c096e84..935ea613 100644 --- a/vino_launch/param/image_object_server_oss.yaml +++ b/vino_launch/param/image_object_server_oss.yaml @@ -3,7 +3,7 @@ Pipelines: inputs: [Image] infers: - name: ObjectDetection - model: /opt/openvino_toolkit/open_model_zoo/model_downloader/object_detection/common/ssd/300/caffe/output/ssd300.xml + model: /opt/openvino_toolkit/open_model_zoo/model_downloader/object_detection/common/mobilenet-ssd/caffe/output/FP32/mobilenet-ssd.xml engine: CPU label: to/be/set/xxx.labels batch: 16 diff --git a/vino_launch/param/image_people_server.yaml b/vino_launch/param/image_people_server.yaml index 858e8afd..2705ba63 100644 --- a/vino_launch/param/image_people_server.yaml +++ b/vino_launch/param/image_people_server.yaml @@ -1,39 +1,39 @@ Pipelines: - name: people - inputs: [StandardCamera] + inputs: [Image] infers: - - name: face_detection - model: /opt/intel/computer_vision_sdk/deployment_tools/model_downloader/Transportation/object_detection/face/pruned_mobilenet_reduced_ssd_shared_weights/dldt/face-detection-adas-0001.xml + - name: FaceDetection + model: /opt/intel/computer_vision_sdk/deployment_tools/intel_models/face-detection-adas-0001/FP32/face-detection-adas-0001.xml engine: CPU label: to/be/set/xxx.labels batch: 1 - - name: age_gender_detection - model: /opt/intel/computer_vision_sdk/deployment_tools/model_downloader/Retail/object_attributes/age_gender/dldt/age-gender-recognition-retail-0013.xml + - name: AgeGenderRecognition + model: /opt/intel/computer_vision_sdk/deployment_tools/intel_models/age-gender-recognition-retail-0013/FP32/age-gender-recognition-retail-0013.xml engine: CPU label: to/be/set/xxx.labels batch: 16 - - name: emotion_detection - model: /opt/intel/computer_vision_sdk/deployment_tools/model_downloader/Retail/object_attributes/emotions_recognition/0003/dldt/emotions-recognition-retail-0003.xml + - name: EmotionRecognition + model: /opt/intel/computer_vision_sdk/deployment_tools/intel_models/emotions-recognition-retail-0003/FP32/emotions-recognition-retail-0003.xml engine: CPU label: to/be/set/xxx.labels batch: 16 - - name: head_pose_detection - model: /opt/intel/computer_vision_sdk/deployment_tools/model_downloader/Transportation/object_attributes/headpose/vanilla_cnn/dldt/head-pose-estimation-adas-0001.xml + - name: HeadPoseEstimation + model: /opt/intel/computer_vision_sdk/deployment_tools/intel_models/head-pose-estimation-adas-0001/FP32/head-pose-estimation-adas-0001.xml engine: CPU label: to/be/set/xxx.labels batch: 16 outputs: [RosService] confidence_threshold: 0.2 connects: - - left: StandardCamera - right: [face_detection] - - left: face_detection - right: [age_gender_detection, emotion_detection, head_pose_detection, RosService] - - left: age_gender_detection + - left: Image + right: [FaceDetection] + - left: FaceDetection + right: [AgeGenderRecognition, EmotionRecognition, HeadPoseEstimation, RosService] + - left: AgeGenderRecognition right: [RosService] - - left: emotion_detection + - left: EmotionRecognition right: [RosService] - - left: head_pose_detection + - left: HeadPoseEstimation right: [RosService] - + input_path: "/opt/openvino_toolkit/ros_openvino_toolkit/data/images/team.jpg" OpenvinoCommon: diff --git a/vino_launch/param/image_people_server_oss.yaml b/vino_launch/param/image_people_server_oss.yaml index 8f375dfd..3e0a12ca 100644 --- a/vino_launch/param/image_people_server_oss.yaml +++ b/vino_launch/param/image_people_server_oss.yaml @@ -1,23 +1,23 @@ Pipelines: - name: people - inputs: [StandardCamera] + inputs: [Image] infers: - - name: face_detection + - name: FaceDetection model: /opt/openvino_toolkit/open_model_zoo/model_downloader/Transportation/object_detection/face/pruned_mobilenet_reduced_ssd_shared_weights/dldt/face-detection-adas-0001.xml engine: CPU label: to/be/set/xxx.labels batch: 1 - - name: age_gender_detection + - name: AgeGenderRecognition model: /opt/openvino_toolkit/open_model_zoo/model_downloader/Retail/object_attributes/age_gender/dldt/age-gender-recognition-retail-0013.xml engine: CPU label: to/be/set/xxx.labels batch: 16 - - name: emotion_detection + - name: EmotionRecognition model: /opt/openvino_toolkit/open_model_zoo/model_downloader/Retail/object_attributes/emotions_recognition/0003/dldt/emotions-recognition-retail-0003.xml engine: CPU label: to/be/set/xxx.labels batch: 16 - - name: head_pose_detection + - name: HeadPoseEstimation model: /opt/openvino_toolkit/open_model_zoo/model_downloader/Transportation/object_attributes/headpose/vanilla_cnn/dldt/head-pose-estimation-adas-0001.xml engine: CPU label: to/be/set/xxx.labels @@ -25,15 +25,15 @@ Pipelines: outputs: [RosService] confidence_threshold: 0.2 connects: - - left: StandardCamera - right: [face_detection] - - left: face_detection - right: [age_gender_detection, emotion_detection, head_pose_detection, RosService] - - left: age_gender_detection + - left: Image + right: [FaceDetection] + - left: FaceDetection + right: [AgeGenderRecognition, EmotionRecognition, HeadPoseEstimation, RosService] + - left: AgeGenderRecognition right: [RosService] - - left: emotion_detection + - left: EmotionRecognition right: [RosService] - - left: head_pose_detection + - left: HeadPoseEstimation right: [RosService] - + input_path: "/opt/openvino_toolkit/ros_openvino_toolkit/data/images/team.jpg" OpenvinoCommon: diff --git a/vino_launch/param/pipeline_image.yaml b/vino_launch/param/pipeline_image.yaml index 27b6f570..95c21b6a 100644 --- a/vino_launch/param/pipeline_image.yaml +++ b/vino_launch/param/pipeline_image.yaml @@ -3,38 +3,38 @@ Pipelines: inputs: [Image] input_path: /opt/openvino_toolkit/ros_openvino_toolkit/data/images/team.jpg infers: - - name: face_detection - model: /opt/intel/computer_vision_sdk/deployment_tools/model_downloader/Transportation/object_detection/face/pruned_mobilenet_reduced_ssd_shared_weights/dldt/face-detection-adas-0001.xml + - name: FaceDetection + model: /opt/intel/computer_vision_sdk/deployment_tools/intel_models/face-detection-adas-0001/FP32/face-detection-adas-0001.xml engine: CPU label: to/be/set/xxx.labels batch: 1 - - name: age_gender_detection - model: /opt/intel/computer_vision_sdk/deployment_tools/model_downloader/Retail/object_attributes/age_gender/dldt/age-gender-recognition-retail-0013.xml + - name: AgeGenderRecognition + model: /opt/intel/computer_vision_sdk/deployment_tools/intel_models/age-gender-recognition-retail-0013/FP32/age-gender-recognition-retail-0013.xml engine: CPU label: to/be/set/xxx.labels batch: 16 - - name: emotion_detection - model: /opt/intel/computer_vision_sdk/deployment_tools/model_downloader/Retail/object_attributes/emotions_recognition/0003/dldt/emotions-recognition-retail-0003.xml + - name: EmotionRecognition + model: /opt/intel/computer_vision_sdk/deployment_tools/intel_models/emotions-recognition-retail-0003/FP32/emotions-recognition-retail-0003.xml engine: CPU label: to/be/set/xxx.labels batch: 16 - - name: head_pose_detection - model: /opt/intel/computer_vision_sdk/deployment_tools/model_downloader/Transportation/object_attributes/headpose/vanilla_cnn/dldt/head-pose-estimation-adas-0001.xml + - name: HeadPoseEstimation + model: /opt/intel/computer_vision_sdk/deployment_tools/intel_models/head-pose-estimation-adas-0001/FP32/head-pose-estimation-adas-0001.xml engine: CPU label: to/be/set/xxx.labels batch: 16 - outputs: [ImageWindow] + outputs: [ImageWindow, RosTopic, RViz] confidence_threshold: 0.2 connects: - left: Image - right: [face_detection] - - left: face_detection - right: [age_gender_detection, emotion_detection, head_pose_detection, ImageWindow] - - left: age_gender_detection - right: [ImageWindow] - - left: emotion_detection - right: [ImageWindow] - - left: head_pose_detection - right: [ImageWindow] + right: [FaceDetection] + - left: FaceDetection + right: [AgeGenderRecognition, EmotionRecognition, HeadPoseEstimation, ImageWindow, RosTopic RViz] + - left: AgeGenderRecognition + right: [ImageWindow, RosTopic, RViz] + - left: EmotionRecognition + right: [ImageWindow, RosTopic, RViz] + - left: HeadPoseEstimation + right: [ImageWindow, RosTopic, RViz] OpenvinoCommon: diff --git a/vino_launch/param/pipeline_image_oss.yaml b/vino_launch/param/pipeline_image_oss.yaml index 2fc4352b..5c87fcb8 100644 --- a/vino_launch/param/pipeline_image_oss.yaml +++ b/vino_launch/param/pipeline_image_oss.yaml @@ -3,38 +3,38 @@ Pipelines: inputs: [Image] input_path: /opt/openvino_toolkit/ros_openvino_toolkit/data/images/team.jpg infers: - - name: face_detection + - name: FaceDetection model: /opt/openvino_toolkit/open_model_zoo/model_downloader/Transportation/object_detection/face/pruned_mobilenet_reduced_ssd_shared_weights/dldt/face-detection-adas-0001.xml engine: CPU label: to/be/set/xxx.labels batch: 1 - - name: age_gender_detection + - name: AgeGenderRecognition model: /opt/openvino_toolkit/open_model_zoo/model_downloader/Retail/object_attributes/age_gender/dldt/age-gender-recognition-retail-0013.xml engine: CPU label: to/be/set/xxx.labels batch: 16 - - name: emotion_detection + - name: EmotionRecognition model: /opt/openvino_toolkit/open_model_zoo/model_downloader/Retail/object_attributes/emotions_recognition/0003/dldt/emotions-recognition-retail-0003.xml engine: CPU label: to/be/set/xxx.labels batch: 16 - - name: head_pose_detection + - name: HeadPoseEstimation model: /opt/openvino_toolkit/open_model_zoo/model_downloader/Transportation/object_attributes/headpose/vanilla_cnn/dldt/head-pose-estimation-adas-0001.xml engine: CPU label: to/be/set/xxx.labels batch: 16 - outputs: [ImageWindow] + outputs: [ImageWindow, RosTopic,RViz] confidence_threshold: 0.2 connects: - left: Image - right: [face_detection] - - left: face_detection - right: [age_gender_detection, emotion_detection, head_pose_detection, ImageWindow] - - left: age_gender_detection - right: [ImageWindow] - - left: emotion_detection - right: [ImageWindow] - - left: head_pose_detection - right: [ImageWindow] + right: [FaceDetection] + - left: FaceDetection + right: [AgeGenderRecognition, EmotionRecognition, HeadPoseEstimation, ImageWindow, RosTopic, Rviz] + - left: AgeGenderRecognition + right: [ImageWindow, RosTopic,RViz] + - left: EmotionRecognition + right: [ImageWindow, RosTopic,RViz] + - left: HeadPoseEstimation + right: [ImageWindow, RosTopic,RViz] OpenvinoCommon: diff --git a/vino_launch/param/pipeline_object.yaml b/vino_launch/param/pipeline_object.yaml index 08bf2ad5..245ba470 100644 --- a/vino_launch/param/pipeline_object.yaml +++ b/vino_launch/param/pipeline_object.yaml @@ -1,16 +1,16 @@ Pipelines: - name: object - inputs: [StandardCamera] + inputs: [RealSenseCamera] infers: - name: ObjectDetection - model: /opt/intel/computer_vision_sdk/deployment_tools/model_downloader/object_detection/common/ssd/300/caffe/output/ssd300.xml - engine: CPU + model: /opt/intel/computer_vision_sdk/deployment_tools/model_downloader/object_detection/common/mobilenet-ssd/caffe/output/FP16/mobilenet-ssd.xml + engine: MYRIAD label: to/be/set/xxx.labels batch: 16 outputs: [ImageWindow, RosTopic, RViz] confidence_threshold: 0.5 connects: - - left: StandardCamera + - left: RealSenseCamera right: [ObjectDetection] - left: ObjectDetection right: [ImageWindow] diff --git a/vino_launch/param/pipeline_object_oss.yaml b/vino_launch/param/pipeline_object_oss.yaml index 354def8b..4fe4ca7a 100644 --- a/vino_launch/param/pipeline_object_oss.yaml +++ b/vino_launch/param/pipeline_object_oss.yaml @@ -3,7 +3,7 @@ Pipelines: inputs: [RealSenseCamera] infers: - name: ObjectDetection - model: /opt/openvino_toolkit/open_model_zoo/model_downloader/object_detection/common/ssd/300/caffe/output/ssd300.xml + model: /opt/intel/computer_vision_sdk/deployment_tools/model_downloader/object_detection/common/mobilenet-ssd/caffe/output/FP16/mobilenet-ssd.xml engine: CPU label: to/be/set/xxx.labels batch: 16 diff --git a/vino_launch/param/pipeline_object_oss_topic.yaml b/vino_launch/param/pipeline_object_oss_topic.yaml index efbd678b..a29b85d1 100644 --- a/vino_launch/param/pipeline_object_oss_topic.yaml +++ b/vino_launch/param/pipeline_object_oss_topic.yaml @@ -3,7 +3,7 @@ Pipelines: inputs: [RealSenseCameraTopic] infers: - name: ObjectDetection - model: /opt/openvino_toolkit/open_model_zoo/model_downloader/object_detection/common/ssd/300/caffe/output/ssd300.xml + model: /opt/openvino_toolkit/open_model_zoo/model_downloader/object_detection/common/mobilenet-ssd/caffe/output/FP32/mobilenet-ssd.xml engine: CPU label: to/be/set/xxx.labels batch: 16 diff --git a/vino_launch/param/pipeline_object_myriad.yaml b/vino_launch/param/pipeline_object_topic.yaml similarity index 65% rename from vino_launch/param/pipeline_object_myriad.yaml rename to vino_launch/param/pipeline_object_topic.yaml index a1f0daa4..8fb74e10 100644 --- a/vino_launch/param/pipeline_object_myriad.yaml +++ b/vino_launch/param/pipeline_object_topic.yaml @@ -1,16 +1,16 @@ Pipelines: - name: object - inputs: [StandardCamera] + inputs: [RealSenseCameraTopic] infers: - name: ObjectDetection - model: /opt/openvino_toolkit/open_model_zoo/model_downloader/object_detection/common/mobilenet-ssd/caffe/output/FP32/mobilenet-ssd.xml + model: /opt/intel/computer_vision_sdk/deployment_tools/model_downloader/object_detection/common/mobilenet-ssd/caffe/output/FP16/mobilenet-ssd.xml engine: MYRIAD label: to/be/set/xxx.labels batch: 16 outputs: [ImageWindow, RosTopic, RViz] confidence_threshold: 0.5 connects: - - left: StandardCamera + - left: RealSenseCameraTopic right: [ObjectDetection] - left: ObjectDetection right: [ImageWindow] diff --git a/vino_launch/param/pipeline_people.yaml b/vino_launch/param/pipeline_people_myriad.yaml similarity index 53% rename from vino_launch/param/pipeline_people.yaml rename to vino_launch/param/pipeline_people_myriad.yaml index e58f80de..30dc280a 100644 --- a/vino_launch/param/pipeline_people.yaml +++ b/vino_launch/param/pipeline_people_myriad.yaml @@ -2,38 +2,38 @@ Pipelines: - name: people inputs: [StandardCamera] infers: - - name: face_detection - model: /opt/intel/computer_vision_sdk/deployment_tools/intel_models/face-detection-adas-0001/FP32/face-detection-adas-0001.xml - engine: CPU + - name: FaceDetection + model: /opt/intel/computer_vision_sdk/deployment_tools/intel_models/face-detection-adas-0001/FP16/face-detection-adas-0001.xml + engine: MYRIAD label: to/be/set/xxx.labels batch: 1 - - name: age_gender_detection - model: /opt/intel/computer_vision_sdk/deployment_tools/intel_models/age-gender-recognition-retail-0013/FP32/age-gender-recognition-retail-0013.xml - engine: CPU + - name: AgeGenderRecognition + model: /opt/intel/computer_vision_sdk/deployment_tools/intel_models/age-gender-recognition-retail-0013/FP16/age-gender-recognition-retail-0013.xml + engine: MYRIAD label: to/be/set/xxx.labels batch: 16 - - name: emotion_detection - model: /opt/intel/computer_vision_sdk/deployment_tools/intel_models/emotions-recognition-retail-0003/FP32/emotions-recognition-retail-0003.xml - engine: CPU + - name: EmotionRecognition + model: /opt/intel/computer_vision_sdk/deployment_tools/intel_models/emotions-recognition-retail-0003/FP16/emotions-recognition-retail-0003.xml + engine: MYRIAD label: to/be/set/xxx.labels batch: 16 - - name: head_pose_detection - model: /opt/intel/computer_vision_sdk/deployment_tools/intel_models/head-pose-estimation-adas-0001/FP32/head-pose-estimation-adas-0001.xml - engine: CPU + - name: HeadPoseEstimation + model: /opt/intel/computer_vision_sdk/deployment_tools/intel_models/head-pose-estimation-adas-0001/FP16/head-pose-estimation-adas-0001.xml + engine: MYRIAD label: to/be/set/xxx.labels batch: 16 outputs: [ImageWindow, RosTopic,RViz] confidence_threshold: 0.2 connects: - left: StandardCamera - right: [face_detection] - - left: face_detection - right: [age_gender_detection, emotion_detection, head_pose_detection, ImageWindow, RosTopic, Rviz] - - left: age_gender_detection + right: [FaceDetection] + - left: FaceDetection + right: [AgeGenderRecognition, EmotionRecognition, HeadPoseEstimation, ImageWindow, RosTopic, RViz] + - left: AgeGenderRecognition right: [ImageWindow, RosTopic,RViz] - - left: emotion_detection + - left: EmotionRecognition right: [ImageWindow, RosTopic,RViz] - - left: head_pose_detection + - left: HeadPoseEstimation right: [ImageWindow, RosTopic,RViz] OpenvinoCommon: diff --git a/vino_launch/param/pipeline_people_oss.yaml b/vino_launch/param/pipeline_people_oss.yaml index 17f4772a..dd000e34 100644 --- a/vino_launch/param/pipeline_people_oss.yaml +++ b/vino_launch/param/pipeline_people_oss.yaml @@ -2,22 +2,22 @@ Pipelines: - name: people inputs: [StandardCamera] infers: - - name: face_detection + - name: FaceDetection model: /opt/openvino_toolkit/open_model_zoo/model_downloader/Transportation/object_detection/face/pruned_mobilenet_reduced_ssd_shared_weights/dldt/face-detection-adas-0001.xml engine: CPU label: to/be/set/xxx.labels batch: 1 - - name: age_gender_detection + - name: AgeGenderRecognition model: /opt/openvino_toolkit/open_model_zoo/model_downloader/Retail/object_attributes/age_gender/dldt/age-gender-recognition-retail-0013.xml engine: CPU label: to/be/set/xxx.labels batch: 16 - - name: emotion_detection + - name: EmotionRecognition model: /opt/openvino_toolkit/open_model_zoo/model_downloader/Retail/object_attributes/emotions_recognition/0003/dldt/emotions-recognition-retail-0003.xml engine: CPU label: to/be/set/xxx.labels batch: 16 - - name: head_pose_detection + - name: HeadPoseEstimation model: /opt/openvino_toolkit/open_model_zoo/model_downloader/Transportation/object_attributes/headpose/vanilla_cnn/dldt/head-pose-estimation-adas-0001.xml engine: CPU label: to/be/set/xxx.labels @@ -26,14 +26,14 @@ Pipelines: confidence_threshold: 0.2 connects: - left: StandardCamera - right: [face_detection] - - left: face_detection - right: [age_gender_detection, emotion_detection, head_pose_detection, ImageWindow, RosTopic, Rviz] - - left: age_gender_detection + right: [FaceDetection] + - left: FaceDetection + right: [AgeGenderRecognition, EmotionRecognition, HeadPoseEstimation, ImageWindow, RosTopic, Rviz] + - left: AgeGenderRecognition right: [ImageWindow, RosTopic,RViz] - - left: emotion_detection + - left: EmotionRecognition right: [ImageWindow, RosTopic,RViz] - - left: head_pose_detection + - left: HeadPoseEstimation right: [ImageWindow, RosTopic,RViz] OpenvinoCommon: diff --git a/vino_launch/param/pipeline_reidentification.yaml b/vino_launch/param/pipeline_reidentification.yaml index 0722e523..bc0db8a0 100644 --- a/vino_launch/param/pipeline_reidentification.yaml +++ b/vino_launch/param/pipeline_reidentification.yaml @@ -3,25 +3,25 @@ Pipelines: inputs: [StandardCamera] infers: - name: ObjectDetection - model: /opt/intel/computer_vision_sdk/deployment_tools/model_downloader/Retail/object_detection/pedestrian/rmnet_ssd/0013/dldt/person-detection-retail-0013.xml + model: /opt/intel/computer_vision_sdk/deployment_tools/intel_models/person-detection-retail-0013/FP32/person-detection-retail-0013.xml engine: CPU label: to/be/set/xxx.labels batch: 1 confidence_threshold: 0.5 enable_roi_constraint: true # set enable_roi_constraint to false if you don't want to make the inferred ROI (region of interest) constrained into the camera frame - name: PersonReidentification - model:/opt/intel/computer_vision_sdk/deployment_tools/model_downloader/Retail/object_reidentification/pedestrian/rmnet_based/0076/dldt/person-reidentification-retail-0076.xml + model: /opt/intel/computer_vision_sdk/deployment_tools/intel_models/person-reidentification-retail-0076/FP32/person-reidentification-retail-0076.xml engine: CPU label: to/be/set/xxx.labels batch: 1 confidence_threshold: 0.7 - outputs: [ImageWindow, RosTopic] + outputs: [ImageWindow, RosTopic, RViz] connects: - left: StandardCamera right: [ObjectDetection] - left: ObjectDetection right: [PersonReidentification] - left: PersonReidentification - right: [ImageWindow, RosTopic] + right: [ImageWindow, RosTopic, RViz] -OpenvinoCommon: \ No newline at end of file +OpenvinoCommon: diff --git a/vino_launch/param/pipeline_reidentification_oss.yaml b/vino_launch/param/pipeline_reidentification_oss.yaml index e3f03c09..98837f9f 100644 --- a/vino_launch/param/pipeline_reidentification_oss.yaml +++ b/vino_launch/param/pipeline_reidentification_oss.yaml @@ -15,13 +15,13 @@ Pipelines: label: to/be/set/xxx.labels batch: 1 confidence_threshold: 0.7 - outputs: [ImageWindow, RosTopic] + outputs: [ImageWindow, RosTopic, RViz] connects: - left: StandardCamera right: [ObjectDetection] - left: ObjectDetection right: [PersonReidentification] - left: PersonReidentification - right: [ImageWindow, RosTopic] + right: [ImageWindow, RosTopic, RViz] -OpenvinoCommon: \ No newline at end of file +OpenvinoCommon: diff --git a/vino_launch/param/pipeline_segmentation.yaml b/vino_launch/param/pipeline_segmentation.yaml index 439c1e99..e954d8e3 100644 --- a/vino_launch/param/pipeline_segmentation.yaml +++ b/vino_launch/param/pipeline_segmentation.yaml @@ -7,13 +7,17 @@ Pipelines: engine: CPU label: to/be/set/xxx.labels batch: 1 - outputs: [ImageWindow, RosTopic] + outputs: [ImageWindow, RosTopic, RViz] confidence_threshold: 0.2 connects: - left: RealSenseCameraTopic right: [ObjectSegmentation] - left: ObjectSegmentation - right: [ImageWindow, RosTopic] + right: [ImageWindow] + - left: ObjectSegmentation + right: [RosTopic] + - left: ObjectSegmentation + right: [RViz] OpenvinoCommon: diff --git a/vino_launch/param/pipeline_video.yaml b/vino_launch/param/pipeline_video.yaml index a4c6f2c7..bac3f74d 100644 --- a/vino_launch/param/pipeline_video.yaml +++ b/vino_launch/param/pipeline_video.yaml @@ -1,20 +1,20 @@ Pipelines: - name: segmentation inputs: [Video] - input_path: /home/iei/Videos/object_segmentation.MP4 + input_path: /home/intel/Videos/2018-09-26-101439.webm infers: - name: ObjectSegmentation model: /opt/models/mask_rcnn_inception_v2_coco_2018_01_28/output/frozen_inference_graph.xml engine: CPU label: to/be/set/xxx.labels batch: 1 - outputs: [ImageWindow, RosTopic] + outputs: [ImageWindow, RosTopic, RViz] confidence_threshold: 0.2 connects: - left: Video right: [ObjectSegmentation] - left: ObjectSegmentation - right: [ImageWindow, RosTopic] + right: [ImageWindow, RosTopic, RViz] OpenvinoCommon: diff --git a/vino_launch/param/rviz/default.rviz b/vino_launch/param/rviz/default.rviz index 68e492cd..a4c117eb 100644 --- a/vino_launch/param/rviz/default.rviz +++ b/vino_launch/param/rviz/default.rviz @@ -1,6 +1,6 @@ Panels: - Class: rviz/Displays - Help Height: 0 + Help Height: 78 Name: Displays Property Tree Widget: Expanded: @@ -8,7 +8,7 @@ Panels: - /Status1 - /Image1 Splitter Ratio: 0.5 - Tree Height: 284 + Tree Height: 291 - Class: rviz/Selection Name: Selection - Class: rviz/Tool Properties @@ -17,7 +17,7 @@ Panels: - /2D Nav Goal1 - /Publish Point1 Name: Tool Properties - Splitter Ratio: 0.588679016 + Splitter Ratio: 0.5886790156364441 - Class: rviz/Views Expanded: - /Current View1 @@ -28,6 +28,8 @@ Panels: Name: Time SyncMode: 0 SyncSource: Image +Preferences: + PromptSaveOnExit: true Visualization Manager: Class: "" Displays: @@ -37,7 +39,7 @@ Visualization Manager: Color: 160; 160; 164 Enabled: true Line Style: - Line Width: 0.0299999993 + Line Width: 0.029999999329447746 Value: Lines Name: Grid Normal Cell Count: 0 @@ -51,7 +53,7 @@ Visualization Manager: Value: true - Class: rviz/Image Enabled: true - Image Topic: /openvino_toolkit/image_rviz + Image Topic: /ros_openvino_toolkit/image_rviz Max Value: 1 Median window: 5 Min Value: 0 @@ -88,7 +90,7 @@ Visualization Manager: Class: rviz/Orbit Distance: 10 Enable Stereo Rendering: - Stereo Eye Separation: 0.0599999987 + Stereo Eye Separation: 0.05999999865889549 Stereo Focal Distance: 1 Swap Stereo Eyes: false Value: false @@ -97,24 +99,24 @@ Visualization Manager: Y: 0 Z: 0 Focal Shape Fixed Size: true - Focal Shape Size: 0.0500000007 + Focal Shape Size: 0.05000000074505806 Invert Z Axis: false Name: Current View - Near Clip Distance: 0.00999999978 - Pitch: 0.785398006 + Near Clip Distance: 0.009999999776482582 + Pitch: 0.785398006439209 Target Frame: Value: Orbit (rviz) - Yaw: 0.785398006 + Yaw: 0.785398006439209 Saved: ~ Window Geometry: Displays: collapsed: false - Height: 967 + Height: 1145 Hide Left Dock: false Hide Right Dock: false Image: collapsed: false - QMainWindow State: 000000ff00000000fd00000004000000000000016a0000033dfc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006100fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c00610079007301000000280000015d000000d700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d006100670065010000018b000001da0000001600ffffff000000010000010f0000033dfc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a0056006900650077007301000000280000033d000000ad00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000062a0000003efc0100000002fb0000000800540069006d006501000000000000062a0000030000fffffffb0000000800540069006d00650100000000000004500000000000000000000003a50000033d00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + QMainWindow State: 000000ff00000000fd0000000400000000000001d8000003dbfc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000001ae000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d00610067006501000001f1000002270000001600ffffff000000010000010f000003dbfc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003d000003db000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000005fd0000003efc0100000002fb0000000800540069006d00650100000000000005fd000002eb00fffffffb0000000800540069006d006501000000000000045000000000000000000000030a000003db00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 Selection: collapsed: false Time: @@ -123,6 +125,6 @@ Window Geometry: collapsed: false Views: collapsed: false - Width: 1578 - X: 116 - Y: 72 + Width: 1533 + X: 67 + Y: 27 From efd914074ced4696902f397bd0f5677ca99fae1f Mon Sep 17 00:00:00 2001 From: RachelRen05 <38059915+RachelRen05@users.noreply.github.com> Date: Mon, 1 Apr 2019 14:25:51 +0800 Subject: [PATCH 09/15] Update OPEN_SOURCE_CODE_README.md --- doc/OPEN_SOURCE_CODE_README.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/doc/OPEN_SOURCE_CODE_README.md b/doc/OPEN_SOURCE_CODE_README.md index adc94e0c..b1a6068e 100644 --- a/doc/OPEN_SOURCE_CODE_README.md +++ b/doc/OPEN_SOURCE_CODE_README.md @@ -37,7 +37,7 @@ This project is a ROS wrapper for CV API of [OpenVINO™](https://software.intel ## 3. Environment Setup **Note**:You can choose to build the environment using *./environment_setup.sh* script in the script subfolder. ```bash -./environment_setup.sh username password +./environment_setup.sh ``` **Note**:You can also choose to follow the steps below to build the environment step by step. - For Ubuntu16.04, install ROS Kinetic Desktop-Full [(guide)](http://wiki.ros.org/kinetic/Installation/Ubuntu) @@ -136,7 +136,6 @@ This project is a ROS wrapper for CV API of [OpenVINO™](https://software.intel ``` * Build package - **Note**:Please modify kinetic to melodic if you are Ubuntu 18.04 user ``` # Ubuntu 16.04 source /opt/ros/kinetic/setup.bash @@ -149,3 +148,4 @@ This project is a ROS wrapper for CV API of [OpenVINO™](https://software.intel sudo ln -s ~/catkin_ws/src/ros_openvino_toolkit /opt/openvino_toolkit/ros_openvino_toolkit ``` +###### *Any security issue should be reported using process at https://01.org/security* From e888b3ff3896a9831aa5e08fb4c68aa5c03700a7 Mon Sep 17 00:00:00 2001 From: RachelRen05 <38059915+RachelRen05@users.noreply.github.com> Date: Mon, 1 Apr 2019 14:27:00 +0800 Subject: [PATCH 10/15] Update README.md --- README.md | 1 + 1 file changed, 1 insertion(+) diff --git a/README.md b/README.md index 2abceb8b..c050778d 100644 --- a/README.md +++ b/README.md @@ -269,3 +269,4 @@ One-step installation scripts are provided for the dependencies' installation. P * ros OpenVINO discription writen in Chinese: https://mp.weixin.qq.com/s/BgG3RGauv5pmHzV_hkVAdw +###### *Any security issue should be reported using process at https://01.org/security* From e699d4262ff9b2ecd0a9236261cd8e05605c1b50 Mon Sep 17 00:00:00 2001 From: RachelRen05 Date: Fri, 26 Apr 2019 17:56:21 +0800 Subject: [PATCH 11/15] fix object_msg/maskinboxes type define conflict --- .../src/outputs/ros_service_output.cpp | 14 ++++++++---- sample/src/image_object_client.cpp | 22 +++++++++---------- 2 files changed, 21 insertions(+), 15 deletions(-) diff --git a/dynamic_vino_lib/src/outputs/ros_service_output.cpp b/dynamic_vino_lib/src/outputs/ros_service_output.cpp index 06a88e2a..f05c21d7 100644 --- a/dynamic_vino_lib/src/outputs/ros_service_output.cpp +++ b/dynamic_vino_lib/src/outputs/ros_service_output.cpp @@ -22,7 +22,7 @@ #include #include "dynamic_vino_lib/outputs/ros_service_output.h" #include "cv_bridge/cv_bridge.h" - +#include // Outputs::RosServiceOutput::RosServiceOutput() @@ -30,9 +30,13 @@ void Outputs::RosServiceOutput::setServiceResponse( boost::shared_ptr response) { if (object_msg_ptr_ != nullptr && object_msg_ptr_->objects_vector.size() > 0) { - response->objects.objects_vector = object_msg_ptr_->objects_vector; + object_msgs::ObjectsInBoxes objs; + objs.objects_vector = object_msg_ptr_->objects_vector; + response->objects.push_back(objs); } else if (faces_msg_ptr_ != nullptr && faces_msg_ptr_ ->objects_vector.size() > 0) { - response->objects.objects_vector = faces_msg_ptr_->objects_vector; + object_msgs::ObjectsInBoxes objs; + objs.objects_vector = faces_msg_ptr_->objects_vector; + response->objects.push_back(objs); } } @@ -40,7 +44,9 @@ void Outputs::RosServiceOutput::setResponseForFace( boost::shared_ptr response) { if (faces_msg_ptr_ != nullptr && faces_msg_ptr_->objects_vector.size() > 0) { - response->objects.objects_vector = faces_msg_ptr_->objects_vector; + object_msgs::ObjectsInBoxes objs; + objs.objects_vector = faces_msg_ptr_->objects_vector; + response->objects.push_back(objs); } } diff --git a/sample/src/image_object_client.cpp b/sample/src/image_object_client.cpp index 3ce85e3a..1cdddb9a 100644 --- a/sample/src/image_object_client.cpp +++ b/sample/src/image_object_client.cpp @@ -55,23 +55,23 @@ int main(int argc, char ** argv) int width = image.cols; int height = image.rows; - for (unsigned int i = 0; i < srv.response.objects.objects_vector.size(); i++) { + for (unsigned int i = 0; i < srv.response.objects[0].objects_vector.size(); i++) { std::stringstream ss; - ss << srv.response.objects.objects_vector[i].object.object_name << ": " << - srv.response.objects.objects_vector[i].object.probability * 100 << "%"; + ss << srv.response.objects[0].objects_vector[i].object.object_name << ": " << + srv.response.objects[0].objects_vector[i].object.probability * 100 << "%"; ROS_INFO("%d: object: %s", i, - srv.response.objects.objects_vector[i].object.object_name.c_str()); + srv.response.objects[0].objects_vector[i].object.object_name.c_str()); ROS_INFO( "prob: %f", - srv.response.objects.objects_vector[i].object.probability); + srv.response.objects[0].objects_vector[i].object.probability); ROS_INFO( "location: (%d, %d, %d, %d)", - srv.response.objects.objects_vector[i].roi.x_offset, srv.response.objects.objects_vector[i].roi.y_offset, - srv.response.objects.objects_vector[i].roi.width, srv.response.objects.objects_vector[i].roi.height); + srv.response.objects[0].objects_vector[i].roi.x_offset, srv.response.objects[0].objects_vector[i].roi.y_offset, + srv.response.objects[0].objects_vector[i].roi.width, srv.response.objects[0].objects_vector[i].roi.height); - int xmin = srv.response.objects.objects_vector[i].roi.x_offset; - int ymin = srv.response.objects.objects_vector[i].roi.y_offset; - int w = srv.response.objects.objects_vector[i].roi.width; - int h = srv.response.objects.objects_vector[i].roi.height; + int xmin = srv.response.objects[0].objects_vector[i].roi.x_offset; + int ymin = srv.response.objects[0].objects_vector[i].roi.y_offset; + int w = srv.response.objects[0].objects_vector[i].roi.width; + int h = srv.response.objects[0].objects_vector[i].roi.height; int xmax = ((xmin + w) < width) ? (xmin + w) : width; int ymax = ((ymin + h) < height) ? (ymin + h) : height; From 84b2d4f9f17fd71d19d57ecf5335cb301c271fa5 Mon Sep 17 00:00:00 2001 From: RachelRen05 Date: Sun, 28 Apr 2019 21:32:38 +0800 Subject: [PATCH 12/15] replace the ssd300 model in object detection with mobilenet --- vino_launch/param/pipeline_object.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/vino_launch/param/pipeline_object.yaml b/vino_launch/param/pipeline_object.yaml index 47ac9dae..d4f5fffe 100644 --- a/vino_launch/param/pipeline_object.yaml +++ b/vino_launch/param/pipeline_object.yaml @@ -3,7 +3,7 @@ Pipelines: inputs: [RealSenseCamera] infers: - name: ObjectDetection - model: /opt/intel/computer_vision_sdk/deployment_tools/model_downloader/object_detection/common/ssd/300/caffe/output/ssd300.xml + model: /opt/intel/computer_vision_sdk/deployment_tools/model_downloader/object_detection/common/mobilenet-ssd/caffe/output/FP16/mobilenet-ssd.xml engine: GPU label: to/be/set/xxx.labels batch: 16 From 2d242e0399fca390491869c61d1508ebca7ec7e0 Mon Sep 17 00:00:00 2001 From: Chao Li Date: Mon, 29 Apr 2019 10:48:43 +0800 Subject: [PATCH 13/15] fix README typo --- README.md | 4 ---- 1 file changed, 4 deletions(-) diff --git a/README.md b/README.md index 630b0ac8..9491d841 100644 --- a/README.md +++ b/README.md @@ -267,8 +267,4 @@ One-step installation scripts are provided for the dependencies' installation. P # More Information * ros OpenVINO discription writen in Chinese: https://mp.weixin.qq.com/s/BgG3RGauv5pmHzV_hkVAdw -<<<<<<< HEAD -======= - ->>>>>>> devel ###### *Any security issue should be reported using process at https://01.org/security* From 2c3b09354d614e0804a5ab9302509ac152f7ae8a Mon Sep 17 00:00:00 2001 From: Chao Li Date: Tue, 30 Apr 2019 11:07:16 +0800 Subject: [PATCH 14/15] Update BINARY_VERSION_README.md --- doc/BINARY_VERSION_README.md | 1 + 1 file changed, 1 insertion(+) diff --git a/doc/BINARY_VERSION_README.md b/doc/BINARY_VERSION_README.md index c8bc2532..f4d731c8 100644 --- a/doc/BINARY_VERSION_README.md +++ b/doc/BINARY_VERSION_README.md @@ -121,6 +121,7 @@ git checkout 2.1.3 source /opt/ros/kinetic/setup.bash # Ubuntu 18.04 source /opt/ros/melodic/setup.bash + source /opt/intel/computer_vision_sdk/bin/setupvars.sh export OpenCV_DIR=$HOME/code/opencv/build cd ~/catkin_ws From 5a0c720b4bcc8440d5db8e9e5d7f7f3a7160695f Mon Sep 17 00:00:00 2001 From: Chao Li Date: Tue, 30 Apr 2019 11:07:48 +0800 Subject: [PATCH 15/15] Update OPEN_SOURCE_CODE_README.md --- doc/OPEN_SOURCE_CODE_README.md | 1 + 1 file changed, 1 insertion(+) diff --git a/doc/OPEN_SOURCE_CODE_README.md b/doc/OPEN_SOURCE_CODE_README.md index 12e99102..c03a66a8 100644 --- a/doc/OPEN_SOURCE_CODE_README.md +++ b/doc/OPEN_SOURCE_CODE_README.md @@ -141,6 +141,7 @@ This project is a ROS wrapper for CV API of [OpenVINO™](https://software.intel source /opt/ros/kinetic/setup.bash # Ubuntu 18.04 source /opt/ros/melodic/setup.bash + cd ~/catkin_ws catkin_make source devel/setup.bash