From 7a0efd517d7ca1b9e0df5e5704adb3feaf93102f Mon Sep 17 00:00:00 2001 From: wujiawei Date: Thu, 24 Nov 2022 12:47:38 +0800 Subject: [PATCH 1/6] upgrade maskrcnn --- .../object_segmentation_maskrcnn.cpp | 240 ++++++++++++++++++ .../object_segmentation_maskrcnn_model.cpp | 229 +++++++++++++++++ .../src/outputs/image_window_output.cpp | 35 ++- 3 files changed, 499 insertions(+), 5 deletions(-) create mode 100644 dynamic_vino_lib/src/inferences/object_segmentation_maskrcnn.cpp create mode 100644 dynamic_vino_lib/src/models/object_segmentation_maskrcnn_model.cpp diff --git a/dynamic_vino_lib/src/inferences/object_segmentation_maskrcnn.cpp b/dynamic_vino_lib/src/inferences/object_segmentation_maskrcnn.cpp new file mode 100644 index 00000000..33946386 --- /dev/null +++ b/dynamic_vino_lib/src/inferences/object_segmentation_maskrcnn.cpp @@ -0,0 +1,240 @@ +// 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 + +#include +#include "dynamic_vino_lib/inferences/object_segmentation.hpp" +#include "dynamic_vino_lib/outputs/base_output.hpp" +#include "dynamic_vino_lib/slog.hpp" + +// 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) +{ + slog::info << "Loading Network: " << network->getModelCategory() << slog::endl; + valid_model_ = network; + setMaxBatchSize(network->getMaxBatchSize()); +} + +/** + * Deprecated! + * This function only support OpenVINO version <=2018R5 + */ +bool dynamic_vino_lib::ObjectSegmentation::enqueue_for_one_input( + 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::enqueue( + const cv::Mat &frame, + const cv::Rect &input_frame_loc) +{ + if (width_ == 0 && height_ == 0) + { + width_ = frame.cols; + height_ = frame.rows; + } + + if (valid_model_ == nullptr || getEngine() == nullptr) + { + throw std::logic_error("Model or Engine is not set correctly!"); + return false; + } + + if (enqueued_frames_ >= valid_model_->getMaxBatchSize()) + { + slog::warn << "Number of " << getName() << "input more than maximum(" << + max_batch_size_ << ") processed by inference" << slog::endl; + return false; + } + + if (!valid_model_->enqueue(getEngine(), frame, input_frame_loc)) + { + return false; + } + + enqueued_frames_ += 1; + 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(); + ov::InferRequest infer_request = getEngine()->getRequest(); + slog::debug << "Analyzing Detection results..." << slog::endl; + std::string detection_output = valid_model_->getOutputName("detection"); + std::string mask_output = valid_model_->getOutputName("masks"); + slog::debug << "Detection_output=" << detection_output << ", Mask_output=" << mask_output << slog::endl; + + //get detection data + ov::Tensor do_tensor = infer_request.get_tensor(detection_output.c_str()); + const auto do_data = do_tensor.data(); + slog::debug << "11111111111" << do_data << slog::endl; + ov::Shape do_shape = do_tensor.get_shape(); + slog::debug << "Detection Blob getDims = " <(); + ov::Shape mask_shape = mask_tensor.get_shape(); + + // determine models + size_t box_description_size = do_shape.back(); + OPENVINO_ASSERT(mask_shape.size() == 4); + size_t box_num = mask_shape[0]; + size_t C = mask_shape[1]; + size_t H = mask_shape[2]; + size_t W = mask_shape[3]; + size_t box_stride = W * H * C; + slog::debug << "box_description is:" << box_description_size << slog::endl; + slog::debug << "box_num is:" << box_num<< slog::endl; + slog::debug << "C is:" << C << slog::endl; + slog::debug << "H is:" << H << slog::endl; + slog::debug << "W is:" << W << slog::endl; + + for (size_t box = 0; box < box_num; ++box) { + // box description: batch, label, prob, x1, y1, x2, y2 + float * box_info = do_data + box * box_description_size; + slog::debug << "box_info is:" << box_info << slog::endl; + auto batch = static_cast(box_info[0]); + slog::debug << "batch =" << batch << slog::endl; + if (batch < 0) { + slog::warn << "Batch size should be greater than 0. [batch=" << batch <<"]." << slog::endl; + 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 = static_cast(x2 - x1); + int box_height = static_cast(y2 - y1); + slog::debug << "Box[" << box_width << "x" << box_height << "]" << slog::endl; + if (box_width <= 0 || box_height <=0) break; + int class_id = static_cast(box_info[1] + 1e-6f); + float * mask_arr = mask_data + box_stride * box + H * W * (class_id - 1); + slog::info << "Detected class " << class_id << " with probability " << prob << " from batch " << batch + << ": [" << x1 << ", " << y1 << "], [" << x2 << ", " << y2 << "]" << slog::endl; + 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; + slog::debug << "adding one segmentation Box ..." << slog::endl; + results_.emplace_back(result); + } + } + if (!found_result) { + slog::debug << "No Segmentation Result Found!" << slog::endl; + results_.clear(); + } + return true; +} + +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_->getModelCategory(); +} + +void dynamic_vino_lib::ObjectSegmentation::observeOutput( + const std::shared_ptr &output) +{ + if (output != nullptr) + { + output->accept(results_); + } +} + +const std::vector dynamic_vino_lib::ObjectSegmentation::getFilteredROIs( + const std::string filter_conditions) const +{ + if (!filter_conditions.empty()) + { + slog::err << "Object segmentation does not support filtering now! " + << "Filter conditions: " << filter_conditions << slog::endl; + } + std::vector filtered_rois; + for (auto res : results_) + { + filtered_rois.push_back(res.getLocation()); + } + return filtered_rois; +} diff --git a/dynamic_vino_lib/src/models/object_segmentation_maskrcnn_model.cpp b/dynamic_vino_lib/src/models/object_segmentation_maskrcnn_model.cpp new file mode 100644 index 00000000..4fdfed5f --- /dev/null +++ b/dynamic_vino_lib/src/models/object_segmentation_maskrcnn_model.cpp @@ -0,0 +1,229 @@ +// 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_segmentation_model.cpp + */ +#include +#include +#include +#include "dynamic_vino_lib/models/object_segmentation_model.hpp" +#include "dynamic_vino_lib/slog.hpp" +#include "dynamic_vino_lib/engines/engine.hpp" + +// Validated Object Segmentation Network +Models::ObjectSegmentationModel::ObjectSegmentationModel( + const std::string & label_loc, + const std::string & model_loc, + int max_batch_size) + : BaseModel(label_loc, model_loc, max_batch_size) +{ +} + +bool Models::ObjectSegmentationModel::enqueue( + const std::shared_ptr &engine, + const cv::Mat &frame, + const cv::Rect &input_frame_loc) +{ + if (engine == nullptr) + { + slog::err << "A frame is trying to be enqueued in a NULL Engine." << slog::endl; + return false; + } + + for (const auto &inputInfoItem : inputs_info_) + { + // Fill first input tensor with images. First b channel, then g and r channels + auto dims = inputInfoItem.get_shape(); + slog::debug << "input tensor shape is:"<< dims.size() <getRequest().get_tensor(inputInfoItem); + auto data = in_tensor.data(); + data[0] = static_cast(frame.rows); // height + data[1] = static_cast(frame.cols); // width + data[2] = 1; + } + } + + return true; +} + +bool Models::ObjectSegmentationModel::matToBlob( + const cv::Mat &orig_image, const cv::Rect &, float scale_factor, + int batch_index, const std::shared_ptr &engine) +{ + (void)scale_factor; + (void)batch_index; + + if (engine == nullptr) + { + slog::err << "A frame is trying to be enqueued in a NULL Engine." << slog::endl; + return false; + } + + ov::InferRequest infer_request = engine->getRequest(); + ov::Tensor input_tensor = infer_request.get_tensor(getInputName("input")); + ov::Shape input_shape = input_tensor.get_shape(); + + OPENVINO_ASSERT(input_shape.size() == 4); + // For frozen graph model: + const size_t width = input_shape[3]; + const size_t height = input_shape[2]; + const size_t channels = input_shape[1]; + + slog::debug <<"width is:"<< width << slog::endl; + slog::debug <<"height is:"<< height << slog::endl; + slog::debug <<"channels is:"<< channels << slog::endl; + slog::debug <<"origin channels is:"<< orig_image.channels() << slog::endl; + slog::debug <<"input shape is:"<< input_shape << slog::endl; + + if (static_cast(orig_image.channels()) != channels) { + throw std::runtime_error("The number of channels for net input and image must match"); + } + + const auto input_data = input_tensor.data(); + cv::Mat resized_image(orig_image); + if (static_cast(width) != orig_image.size().width || + static_cast(height) != orig_image.size().height) { + cv::resize(orig_image, resized_image, cv::Size(width, height)); + } + + int batchOffset = batch_index * width * height * channels; + if (channels == 1) { + for (size_t h = 0; h < height; h++) { + for (size_t w = 0; w < width; w++) { + input_data[batchOffset + h * width + w] = resized_image.at(h, w); + } + } + } else if (channels == 3) { + for (size_t c = 0; c < channels; c++) { + for (size_t h = 0; h < height; h++) { + for (size_t w = 0; w < width; w++) { + input_data[batchOffset + c * width * height + h * width + w] = + resized_image.at(h, w)[c]; + } + } + } + } else { + throw std::runtime_error("Unsupported number of channels"); + } + + return true; +} + +const std::string Models::ObjectSegmentationModel::getModelCategory() const +{ + return "Object Segmentation"; +} + +bool Models::ObjectSegmentationModel::updateLayerProperty( + std::shared_ptr& model) +{ + slog::info<< "Checking INPUTS for Model" <inputs(); + slog::debug<<"input size="<input("image_tensor").get_shape(); + slog::debug<<"image_tensor shape is:"<< input_shape.size() <input("image_info").get_shape(); + slog::debug<<"image_info shape is:"<< info_shape.size() <output("masks").get_shape(); + slog::debug<<"masks shape is:"<< mask_shape.size() <output("reshape_do_2d").get_shape(); + slog::debug<< "detection shape is:" << detection_shape.size() < & results) { - const float alpha = 0.5f; - cv::Mat roi_img = frame_; - cv::Mat colored_mask = results[0].getMask(); - cv::resize(colored_mask,colored_mask,cv::Size(frame_.size().width,frame_.size().height)); - cv::addWeighted(colored_mask, alpha, roi_img, 1.0f - alpha, 0.0f, roi_img); + 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] % colors_.size() ]; + 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(), + cv::Scalar(color[2], color[1], color[0]) ); + roi_img.copyTo(colored_mask, mask <= MASK_THRESHOLD); + +/** + 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( From be62770059ef042424fc3d9b85a4356ad2d1938b Mon Sep 17 00:00:00 2001 From: wujiawei Date: Sun, 27 Nov 2022 17:33:44 +0800 Subject: [PATCH 2/6] add maskrcnn segmentation --- dynamic_vino_lib/CMakeLists.txt | 1 + .../object_segmentation_maskrcnn_model.hpp | 61 +++++++++++++++++++ .../dynamic_vino_lib/pipeline_manager.hpp | 2 + .../dynamic_vino_lib/pipeline_params.hpp | 1 + .../object_segmentation_maskrcnn_model.cpp | 12 ++-- dynamic_vino_lib/src/pipeline_manager.cpp | 20 ++++++ .../pipeline_segmentation_maskrcnn.launch.py | 55 +++++++++++++++++ .../param/pipeline_segmentation_maskrcnn.yaml | 24 ++++++++ 8 files changed, 170 insertions(+), 6 deletions(-) create mode 100644 dynamic_vino_lib/include/dynamic_vino_lib/models/object_segmentation_maskrcnn_model.hpp create mode 100644 sample/launch/pipeline_segmentation_maskrcnn.launch.py create mode 100644 sample/param/pipeline_segmentation_maskrcnn.yaml diff --git a/dynamic_vino_lib/CMakeLists.txt b/dynamic_vino_lib/CMakeLists.txt index 719a4246..69432d69 100644 --- a/dynamic_vino_lib/CMakeLists.txt +++ b/dynamic_vino_lib/CMakeLists.txt @@ -208,6 +208,7 @@ add_library(${PROJECT_NAME} SHARED src/models/face_detection_model.cpp src/models/head_pose_detection_model.cpp src/models/object_segmentation_model.cpp + src/models/object_segmentation_maskrcnn_model.cpp src/models/person_reidentification_model.cpp src/models/person_attribs_detection_model.cpp #src/models/landmarks_detection_model.cpp diff --git a/dynamic_vino_lib/include/dynamic_vino_lib/models/object_segmentation_maskrcnn_model.hpp b/dynamic_vino_lib/include/dynamic_vino_lib/models/object_segmentation_maskrcnn_model.hpp new file mode 100644 index 00000000..81d45bc5 --- /dev/null +++ b/dynamic_vino_lib/include/dynamic_vino_lib/models/object_segmentation_maskrcnn_model.hpp @@ -0,0 +1,61 @@ +// 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 ObjectSegmentationMaskrcnnModel Class + * @file face_detection_model.h + */ +#ifndef DYNAMIC_VINO_LIB__MODELS__OBJECT_SEGMENTATION_MASKRCNN_MODEL_HPP_ +#define DYNAMIC_VINO_LIB__MODELS__OBJECT_SEGMENTATION_MASKRCNN_MODEL_HPP_ +#include +#include +#include "dynamic_vino_lib/models/base_model.hpp" +namespace Models +{ +/** + * @class ObjectSegmentationMaskrcnnModel + * @brief This class generates the object segmentation model. + */ +class ObjectSegmentationMaskrcnnModel : public BaseModel +{ +public: + ObjectSegmentationMaskrcnnModel(const std::string& label_loc, const std::string & model_loc, int batch_size = 1); + inline int getMaxProposalCount() const + { + return max_proposal_count_; + } + inline int getObjectSize() const + { + return object_size_; + } + + bool enqueue(const std::shared_ptr & ,const cv::Mat &, + const cv::Rect & ) override; + + bool matToBlob( + const cv::Mat & , const cv::Rect &, float , + int , const std::shared_ptr & ); + + /** + * @brief Get the name of this segmentation model. + * @return Name of the model. + */ + const std::string getModelCategory() const override; + bool updateLayerProperty(std::shared_ptr&) override; + +private: + int max_proposal_count_; + int object_size_; +}; +} // namespace Models +#endif // DYNAMIC_VINO_LIB__MODELS__OBJECT_SEGMENTATION_MASKRCNN_MODEL_HPP_ diff --git a/dynamic_vino_lib/include/dynamic_vino_lib/pipeline_manager.hpp b/dynamic_vino_lib/include/dynamic_vino_lib/pipeline_manager.hpp index 52016c24..3c464684 100644 --- a/dynamic_vino_lib/include/dynamic_vino_lib/pipeline_manager.hpp +++ b/dynamic_vino_lib/include/dynamic_vino_lib/pipeline_manager.hpp @@ -125,6 +125,8 @@ class PipelineManager std::shared_ptr createObjectSegmentation(const Params::ParamManager::InferenceRawData & infer); std::shared_ptr + createObjectSegmentationMaskrcnn(const Params::ParamManager::InferenceRawData & infer); + std::shared_ptr createPersonReidentification(const Params::ParamManager::InferenceRawData & infer); std::shared_ptr createPersonAttribsDetection(const Params::ParamManager::InferenceRawData & infer); diff --git a/dynamic_vino_lib/include/dynamic_vino_lib/pipeline_params.hpp b/dynamic_vino_lib/include/dynamic_vino_lib/pipeline_params.hpp index 9de08354..ff833276 100644 --- a/dynamic_vino_lib/include/dynamic_vino_lib/pipeline_params.hpp +++ b/dynamic_vino_lib/include/dynamic_vino_lib/pipeline_params.hpp @@ -53,6 +53,7 @@ const char kInferTpye_EmotionRecognition[] = "EmotionRecognition"; const char kInferTpye_HeadPoseEstimation[] = "HeadPoseEstimation"; const char kInferTpye_ObjectDetection[] = "ObjectDetection"; const char kInferTpye_ObjectSegmentation[] = "ObjectSegmentation"; +const char kInferTpye_ObjectSegmentationMaskrcnn[] = "ObjectSegmentationMaskrcnn"; const char kInferTpye_ObjectDetectionTypeSSD[] = "SSD"; const char kInferTpye_ObjectDetectionTypeYolov2[] = "yolov2"; const char kInferTpye_PersonReidentification[] = "PersonReidentification"; diff --git a/dynamic_vino_lib/src/models/object_segmentation_maskrcnn_model.cpp b/dynamic_vino_lib/src/models/object_segmentation_maskrcnn_model.cpp index 4fdfed5f..c1be1682 100644 --- a/dynamic_vino_lib/src/models/object_segmentation_maskrcnn_model.cpp +++ b/dynamic_vino_lib/src/models/object_segmentation_maskrcnn_model.cpp @@ -19,12 +19,12 @@ #include #include #include -#include "dynamic_vino_lib/models/object_segmentation_model.hpp" +#include "dynamic_vino_lib/models/object_segmentation_maskrcnn_model.hpp" #include "dynamic_vino_lib/slog.hpp" #include "dynamic_vino_lib/engines/engine.hpp" // Validated Object Segmentation Network -Models::ObjectSegmentationModel::ObjectSegmentationModel( +Models::ObjectSegmentationMaskrcnnModel::ObjectSegmentationMaskrcnnModel( const std::string & label_loc, const std::string & model_loc, int max_batch_size) @@ -32,7 +32,7 @@ Models::ObjectSegmentationModel::ObjectSegmentationModel( { } -bool Models::ObjectSegmentationModel::enqueue( +bool Models::ObjectSegmentationMaskrcnnModel::enqueue( const std::shared_ptr &engine, const cv::Mat &frame, const cv::Rect &input_frame_loc) @@ -68,7 +68,7 @@ bool Models::ObjectSegmentationModel::enqueue( return true; } -bool Models::ObjectSegmentationModel::matToBlob( +bool Models::ObjectSegmentationMaskrcnnModel::matToBlob( const cv::Mat &orig_image, const cv::Rect &, float scale_factor, int batch_index, const std::shared_ptr &engine) { @@ -131,12 +131,12 @@ bool Models::ObjectSegmentationModel::matToBlob( return true; } -const std::string Models::ObjectSegmentationModel::getModelCategory() const +const std::string Models::ObjectSegmentationMaskrcnnModel::getModelCategory() const { return "Object Segmentation"; } -bool Models::ObjectSegmentationModel::updateLayerProperty( +bool Models::ObjectSegmentationMaskrcnnModel::updateLayerProperty( std::shared_ptr& model) { slog::info<< "Checking INPUTS for Model" < +PipelineManager::createObjectSegmentationMaskrcnn(const Params::ParamManager::InferenceRawData & infer) +{ + auto model = + std::make_shared(infer.label, infer.model, infer.batch); + model->modelInit(); + slog::info << "Segmentation model initialized." << slog::endl; + auto engine = engine_manager_.createEngine(infer.engine, model); + slog::info << "Segmentation Engine initialized." << slog::endl; + auto segmentation_inference_ptr = std::make_shared( + infer.confidence_threshold); + slog::info << "Segmentation Inference instanced." << slog::endl; + segmentation_inference_ptr->loadNetwork(model); + segmentation_inference_ptr->loadEngine(engine); + + return segmentation_inference_ptr; +} + std::shared_ptr PipelineManager::createPersonReidentification( const Params::ParamManager::InferenceRawData & infer) diff --git a/sample/launch/pipeline_segmentation_maskrcnn.launch.py b/sample/launch/pipeline_segmentation_maskrcnn.launch.py new file mode 100644 index 00000000..5ccd9c52 --- /dev/null +++ b/sample/launch/pipeline_segmentation_maskrcnn.launch.py @@ -0,0 +1,55 @@ +# Copyright 2018 Open Source Robotics Foundation, Inc. +# +# 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. + +"""Launch face detection and rviz.""" + +import os + +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +import launch_ros.actions + +from launch.substitutions import LaunchConfiguration, PythonExpression +import launch + +def generate_launch_description(): + #default_yaml = os.path.join(get_package_share_directory('dynamic_vino_sample'), 'param', + #'pipeline_segmentation.yaml') + default_rviz = os.path.join(get_package_share_directory('dynamic_vino_sample'), 'launch', + 'rviz/default.rviz') + return LaunchDescription([ + launch.actions.DeclareLaunchArgument(name='yaml_path', default_value = + os.path.join(get_package_share_directory('dynamic_vino_sample'), 'param','pipeline_segmentation_maskrcnn.yaml')), + # Realsense + # NOTE: Split realsense_node launching from OpenVINO package, which + # will be launched by RDK launching file or manually. + + # Openvino detection + launch_ros.actions.Node( + package='dynamic_vino_sample', + executable='pipeline_with_params', + arguments=['-config', LaunchConfiguration('yaml_path')], + remappings=[ + ('/openvino_toolkit/image_raw', '/camera/color/image_raw'), + ('/openvino_toolkit/segmentation/segmented_obejcts', + '/ros2_openvino_toolkit/segmented_obejcts'), + ('/openvino_toolkit/segmentation/images', '/ros2_openvino_toolkit/image_rviz')], + output='screen'), + + # Rviz + launch_ros.actions.Node( + package='rviz2', + executable='rviz2', output='screen', + arguments=['--display-config', default_rviz]), + ]) diff --git a/sample/param/pipeline_segmentation_maskrcnn.yaml b/sample/param/pipeline_segmentation_maskrcnn.yaml new file mode 100644 index 00000000..667f6211 --- /dev/null +++ b/sample/param/pipeline_segmentation_maskrcnn.yaml @@ -0,0 +1,24 @@ +Pipelines: +- name: segmentation + inputs: [Video] + # input_path: /home/jiawei/test-seg-2022/src/ros2_openvino_toolkit/data/images/road-segmentation.png + input_path: /home/jiawei/openvino_test_video/sample-videos/car-detection.mp4 + infers: + - name: ObjectSegmentationMaskrcnn + model: /home/jiawei/mask_rcnn_inception_v2_coco_2018_01_28/OUT/frozen_inference_graph.xml + engine: CPU #"HETERO:CPU,GPU,MYRIAD" + label: to/be/set/xxx.labels + batch: 1 + confidence_threshold: 0.5 + outputs: [ImageWindow, RosTopic, RViz] + connects: + - left: Video + right: [ObjectSegmentationMaskrcnn] + - left: ObjectSegmentationMaskrcnn + right: [ImageWindow] + - left: ObjectSegmentationMaskrcnn + right: [RosTopic] + - left: ObjectSegmentationMaskrcnn + right: [RViz] + +OpenvinoCommon: From 70b51d13f798a874df01605dc5a9f3dce0d0f4e7 Mon Sep 17 00:00:00 2001 From: wujiawei Date: Sun, 27 Nov 2022 20:43:06 +0800 Subject: [PATCH 3/6] add output --- dynamic_vino_lib/CMakeLists.txt | 1 + .../object_segmentation_maskrcnn.hpp | 146 ++++++++++++++++++ .../dynamic_vino_lib/outputs/base_output.hpp | 7 + .../outputs/image_window_output.hpp | 6 + .../outputs/ros_topic_output.hpp | 6 + .../dynamic_vino_lib/outputs/rviz_output.hpp | 6 + .../object_segmentation_maskrcnn.cpp | 30 ++-- .../object_segmentation_maskrcnn_model.cpp | 2 +- .../src/outputs/ros_topic_output.cpp | 23 +++ dynamic_vino_lib/src/outputs/rviz_output.cpp | 6 + 10 files changed, 217 insertions(+), 16 deletions(-) create mode 100644 dynamic_vino_lib/include/dynamic_vino_lib/inferences/object_segmentation_maskrcnn.hpp diff --git a/dynamic_vino_lib/CMakeLists.txt b/dynamic_vino_lib/CMakeLists.txt index 69432d69..6e893116 100644 --- a/dynamic_vino_lib/CMakeLists.txt +++ b/dynamic_vino_lib/CMakeLists.txt @@ -189,6 +189,7 @@ add_library(${PROJECT_NAME} SHARED src/inferences/object_detection.cpp src/inferences/head_pose_detection.cpp src/inferences/object_segmentation.cpp + src/inferences/object_segmentation_maskrcnn.cpp src/inferences/person_reidentification.cpp src/inferences/person_attribs_detection.cpp #src/inferences/landmarks_detection.cpp diff --git a/dynamic_vino_lib/include/dynamic_vino_lib/inferences/object_segmentation_maskrcnn.hpp b/dynamic_vino_lib/include/dynamic_vino_lib/inferences/object_segmentation_maskrcnn.hpp new file mode 100644 index 00000000..79812426 --- /dev/null +++ b/dynamic_vino_lib/include/dynamic_vino_lib/inferences/object_segmentation_maskrcnn.hpp @@ -0,0 +1,146 @@ +// 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 +#include "dynamic_vino_lib/models/object_segmentation_maskrcnn_model.hpp" +#include "dynamic_vino_lib/engines/engine.hpp" +#include "dynamic_vino_lib/inferences/base_inference.hpp" +#include "openvino/openvino.hpp" +#include "opencv2/opencv.hpp" +// namespace +namespace dynamic_vino_lib +{ +/** + * @class ObjectSegmentationResult + * @brief Class for storing and processing object segmentation result. + */ +class ObjectSegmentationMaskrcnnResult : public Result +{ +public: + friend class ObjectSegmentationMaskrcnn; + explicit ObjectSegmentationMaskrcnnResult(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 ObjectSegmentationMaskrcnn : public BaseInference +{ +public: + using Result = dynamic_vino_lib::ObjectSegmentationMaskrcnnResult; + explicit ObjectSegmentationMaskrcnn(double); + ~ObjectSegmentationMaskrcnn() 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; + + //Deprecated!! + bool enqueue_for_one_input(const cv::Mat &, const cv::Rect &); + + /** + * @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. + */ + 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. + */ + 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; + const std::vector getFilteredROIs( + const std::string filter_conditions) const override; + +private: + std::shared_ptr valid_model_; + std::vector results_; + int width_ = 0; + int height_ = 0; + double show_output_thresh_ = 0; + + 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 dynamic_vino_lib +#endif // DYNAMIC_VINO_LIB__INFERENCES__OBJECT_SEGMENTATION_HPP_ diff --git a/dynamic_vino_lib/include/dynamic_vino_lib/outputs/base_output.hpp b/dynamic_vino_lib/include/dynamic_vino_lib/outputs/base_output.hpp index 7d25944c..3bae23c2 100644 --- a/dynamic_vino_lib/include/dynamic_vino_lib/outputs/base_output.hpp +++ b/dynamic_vino_lib/include/dynamic_vino_lib/outputs/base_output.hpp @@ -50,6 +50,7 @@ #include "dynamic_vino_lib/inferences/face_reidentification.hpp" #include "dynamic_vino_lib/inferences/vehicle_attribs_detection.hpp" #include "dynamic_vino_lib/inferences/license_plate_detection.hpp" +#include "dynamic_vino_lib/inferences/object_segmentation_maskrcnn.hpp" #include "opencv2/opencv.hpp" class Pipeline; @@ -108,6 +109,12 @@ class BaseOutput virtual void accept(const std::vector &) { } + /** + * @brief Generate output content according to the object segmentation maskrcnn result. + */ + virtual void accept(const std::vector &) + { + } /** * @brief Generate output content according to the object detection result. */ diff --git a/dynamic_vino_lib/include/dynamic_vino_lib/outputs/image_window_output.hpp b/dynamic_vino_lib/include/dynamic_vino_lib/outputs/image_window_output.hpp index e34950af..cadead70 100644 --- a/dynamic_vino_lib/include/dynamic_vino_lib/outputs/image_window_output.hpp +++ b/dynamic_vino_lib/include/dynamic_vino_lib/outputs/image_window_output.hpp @@ -98,6 +98,12 @@ class ImageWindowOutput : public BaseOutput * @param[in] An obejct segmentation result objetc. */ void accept(const std::vector &) override; + /** + * @brief Generate image window output content according to + * the object segmentation maskrcnn result. + * @param[in] An obejct segmentation result objetc. + */ + void accept(const std::vector &) override; /** * @brief Generate image window output content according to * the face detection result. diff --git a/dynamic_vino_lib/include/dynamic_vino_lib/outputs/ros_topic_output.hpp b/dynamic_vino_lib/include/dynamic_vino_lib/outputs/ros_topic_output.hpp index c102e44e..cbfaf9d3 100644 --- a/dynamic_vino_lib/include/dynamic_vino_lib/outputs/ros_topic_output.hpp +++ b/dynamic_vino_lib/include/dynamic_vino_lib/outputs/ros_topic_output.hpp @@ -114,6 +114,12 @@ class RosTopicOutput : public BaseOutput * @param[in] results a bundle of object segmentation 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 maskrcnn results. + */ + void accept(const std::vector &) override; /** * @brief Generate ros topic infomation according to * the object detection result. diff --git a/dynamic_vino_lib/include/dynamic_vino_lib/outputs/rviz_output.hpp b/dynamic_vino_lib/include/dynamic_vino_lib/outputs/rviz_output.hpp index 359f8313..54e7e3ec 100644 --- a/dynamic_vino_lib/include/dynamic_vino_lib/outputs/rviz_output.hpp +++ b/dynamic_vino_lib/include/dynamic_vino_lib/outputs/rviz_output.hpp @@ -91,6 +91,12 @@ class RvizOutput : public BaseOutput * @param[in] results A bundle of object segmentation results. */ void accept(const std::vector &) override; + /** + * @brief Generate rviz output content according to + * the object segmentation result. + * @param[in] results A bundle of object segmentation maskrcnn results. + */ + void accept(const std::vector &) override; /** * @brief Generate rviz output content according to * the emotion detection result. diff --git a/dynamic_vino_lib/src/inferences/object_segmentation_maskrcnn.cpp b/dynamic_vino_lib/src/inferences/object_segmentation_maskrcnn.cpp index 33946386..0ad96aad 100644 --- a/dynamic_vino_lib/src/inferences/object_segmentation_maskrcnn.cpp +++ b/dynamic_vino_lib/src/inferences/object_segmentation_maskrcnn.cpp @@ -24,26 +24,26 @@ #include #include -#include "dynamic_vino_lib/inferences/object_segmentation.hpp" +#include "dynamic_vino_lib/inferences/object_segmentation_maskrcnn.hpp" #include "dynamic_vino_lib/outputs/base_output.hpp" #include "dynamic_vino_lib/slog.hpp" // ObjectSegmentationResult -dynamic_vino_lib::ObjectSegmentationResult::ObjectSegmentationResult(const cv::Rect &location) +dynamic_vino_lib::ObjectSegmentationMaskrcnnResult::ObjectSegmentationResult(const cv::Rect &location) : Result(location) { } // ObjectSegmentation -dynamic_vino_lib::ObjectSegmentation::ObjectSegmentation(double show_output_thresh) +dynamic_vino_lib::ObjectSegmentationMaskrcnn::ObjectSegmentation(double show_output_thresh) : show_output_thresh_(show_output_thresh), dynamic_vino_lib::BaseInference() { } -dynamic_vino_lib::ObjectSegmentation::~ObjectSegmentation() = default; +dynamic_vino_lib::ObjectSegmentationMaskrcnn::~ObjectSegmentation() = default; -void dynamic_vino_lib::ObjectSegmentation::loadNetwork( - const std::shared_ptr network) +void dynamic_vino_lib::ObjectSegmentationMaskrcnn::loadNetwork( + const std::shared_ptr network) { slog::info << "Loading Network: " << network->getModelCategory() << slog::endl; valid_model_ = network; @@ -54,7 +54,7 @@ void dynamic_vino_lib::ObjectSegmentation::loadNetwork( * Deprecated! * This function only support OpenVINO version <=2018R5 */ -bool dynamic_vino_lib::ObjectSegmentation::enqueue_for_one_input( +bool dynamic_vino_lib::ObjectSegmentationMaskrcnn::enqueue_for_one_input( const cv::Mat &frame, const cv::Rect &input_frame_loc) { @@ -74,7 +74,7 @@ bool dynamic_vino_lib::ObjectSegmentation::enqueue_for_one_input( return true; } -bool dynamic_vino_lib::ObjectSegmentation::enqueue( +bool dynamic_vino_lib::ObjectSegmentationMaskrcnn::enqueue( const cv::Mat &frame, const cv::Rect &input_frame_loc) { @@ -106,12 +106,12 @@ bool dynamic_vino_lib::ObjectSegmentation::enqueue( return true; } -bool dynamic_vino_lib::ObjectSegmentation::submitRequest() +bool dynamic_vino_lib::ObjectSegmentationMaskrcnn::submitRequest() { return dynamic_vino_lib::BaseInference::submitRequest(); } -bool dynamic_vino_lib::ObjectSegmentation::fetchResults() +bool dynamic_vino_lib::ObjectSegmentationMaskrcnn::fetchResults() { bool can_fetch = dynamic_vino_lib::BaseInference::fetchResults(); @@ -198,23 +198,23 @@ bool dynamic_vino_lib::ObjectSegmentation::fetchResults() return true; } -int dynamic_vino_lib::ObjectSegmentation::getResultsLength() const +int dynamic_vino_lib::ObjectSegmentationMaskrcnn::getResultsLength() const { return static_cast(results_.size()); } const dynamic_vino_lib::Result * -dynamic_vino_lib::ObjectSegmentation::getLocationResult(int idx) const +dynamic_vino_lib::ObjectSegmentationMaskrcnn::getLocationResult(int idx) const { return &(results_[idx]); } -const std::string dynamic_vino_lib::ObjectSegmentation::getName() const +const std::string dynamic_vino_lib::ObjectSegmentationMaskrcnn::getName() const { return valid_model_->getModelCategory(); } -void dynamic_vino_lib::ObjectSegmentation::observeOutput( +void dynamic_vino_lib::ObjectSegmentationMaskrcnn::observeOutput( const std::shared_ptr &output) { if (output != nullptr) @@ -223,7 +223,7 @@ void dynamic_vino_lib::ObjectSegmentation::observeOutput( } } -const std::vector dynamic_vino_lib::ObjectSegmentation::getFilteredROIs( +const std::vector dynamic_vino_lib::ObjectSegmentationMaskrcnn::getFilteredROIs( const std::string filter_conditions) const { if (!filter_conditions.empty()) diff --git a/dynamic_vino_lib/src/models/object_segmentation_maskrcnn_model.cpp b/dynamic_vino_lib/src/models/object_segmentation_maskrcnn_model.cpp index c1be1682..5b8934f0 100644 --- a/dynamic_vino_lib/src/models/object_segmentation_maskrcnn_model.cpp +++ b/dynamic_vino_lib/src/models/object_segmentation_maskrcnn_model.cpp @@ -64,7 +64,7 @@ bool Models::ObjectSegmentationMaskrcnnModel::enqueue( data[2] = 1; } } - + 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 6aa8a9ee..c041a64b 100644 --- a/dynamic_vino_lib/src/outputs/ros_topic_output.cpp +++ b/dynamic_vino_lib/src/outputs/ros_topic_output.cpp @@ -206,6 +206,29 @@ void Outputs::RosTopicOutput::accept( } } +void Outputs::RosTopicOutput::accept( + const std::vector & results) +{ + segmented_objects_topic_ = std::make_shared(); + people_msgs::msg::ObjectInMask object; + for (auto & r : results) { + 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_objects_topic_->objects_vector.push_back(object); + } +} + void Outputs::RosTopicOutput::accept( const std::vector & results) { diff --git a/dynamic_vino_lib/src/outputs/rviz_output.cpp b/dynamic_vino_lib/src/outputs/rviz_output.cpp index a9778ccf..5a98273e 100644 --- a/dynamic_vino_lib/src/outputs/rviz_output.cpp +++ b/dynamic_vino_lib/src/outputs/rviz_output.cpp @@ -85,6 +85,12 @@ void Outputs::RvizOutput::accept( image_window_output_->accept(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); From e5dbd70d68bc7442f769185e88fea14094b8381f Mon Sep 17 00:00:00 2001 From: wujiawei Date: Sun, 27 Nov 2022 22:34:28 +0800 Subject: [PATCH 4/6] fix class name --- .../inferences/object_segmentation_maskrcnn.hpp | 6 +++--- .../src/inferences/object_segmentation_maskrcnn.cpp | 6 +++--- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/dynamic_vino_lib/include/dynamic_vino_lib/inferences/object_segmentation_maskrcnn.hpp b/dynamic_vino_lib/include/dynamic_vino_lib/inferences/object_segmentation_maskrcnn.hpp index 79812426..11dbb044 100644 --- a/dynamic_vino_lib/include/dynamic_vino_lib/inferences/object_segmentation_maskrcnn.hpp +++ b/dynamic_vino_lib/include/dynamic_vino_lib/inferences/object_segmentation_maskrcnn.hpp @@ -16,8 +16,8 @@ * @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_ +#ifndef DYNAMIC_VINO_LIB__INFERENCES__OBJECT_SEGMENTATION_MASKRCNN_HPP_ +#define DYNAMIC_VINO_LIB__INFERENCES__OBJECT_SEGMENTATION_MASKRCNN_HPP_ #include #include #include @@ -34,7 +34,7 @@ namespace dynamic_vino_lib { /** - * @class ObjectSegmentationResult + * @class ObjectSegmentationMaskrcnnResult * @brief Class for storing and processing object segmentation result. */ class ObjectSegmentationMaskrcnnResult : public Result diff --git a/dynamic_vino_lib/src/inferences/object_segmentation_maskrcnn.cpp b/dynamic_vino_lib/src/inferences/object_segmentation_maskrcnn.cpp index 0ad96aad..0426f1cf 100644 --- a/dynamic_vino_lib/src/inferences/object_segmentation_maskrcnn.cpp +++ b/dynamic_vino_lib/src/inferences/object_segmentation_maskrcnn.cpp @@ -29,18 +29,18 @@ #include "dynamic_vino_lib/slog.hpp" // ObjectSegmentationResult -dynamic_vino_lib::ObjectSegmentationMaskrcnnResult::ObjectSegmentationResult(const cv::Rect &location) +dynamic_vino_lib::ObjectSegmentationMaskrcnnResult::ObjectSegmentationMaskrcnnResult(const cv::Rect &location) : Result(location) { } // ObjectSegmentation -dynamic_vino_lib::ObjectSegmentationMaskrcnn::ObjectSegmentation(double show_output_thresh) +dynamic_vino_lib::ObjectSegmentationMaskrcnn::ObjectSegmentationMaskrcnn(double show_output_thresh) : show_output_thresh_(show_output_thresh), dynamic_vino_lib::BaseInference() { } -dynamic_vino_lib::ObjectSegmentationMaskrcnn::~ObjectSegmentation() = default; +dynamic_vino_lib::ObjectSegmentationMaskrcnn::~ObjectSegmentationMaskrcnn() = default; void dynamic_vino_lib::ObjectSegmentationMaskrcnn::loadNetwork( const std::shared_ptr network) From ea560f53ed5d91fb2b8077160f42b630b056fd06 Mon Sep 17 00:00:00 2001 From: wujiawei Date: Mon, 28 Nov 2022 16:35:31 +0800 Subject: [PATCH 5/6] fix pipeline manager and output --- .../outputs/image_window_output.hpp | 1 + .../object_segmentation_maskrcnn.cpp | 2 - .../src/models/object_segmentation_model.cpp | 2 +- .../src/outputs/image_window_output.cpp | 48 +++++++++++++++++++ dynamic_vino_lib/src/pipeline_manager.cpp | 4 +- 5 files changed, 52 insertions(+), 5 deletions(-) diff --git a/dynamic_vino_lib/include/dynamic_vino_lib/outputs/image_window_output.hpp b/dynamic_vino_lib/include/dynamic_vino_lib/outputs/image_window_output.hpp index cadead70..9ea76ef5 100644 --- a/dynamic_vino_lib/include/dynamic_vino_lib/outputs/image_window_output.hpp +++ b/dynamic_vino_lib/include/dynamic_vino_lib/outputs/image_window_output.hpp @@ -151,6 +151,7 @@ class ImageWindowOutput : public BaseOutput cv::Mat getRotationTransform(double yaw, double pitch, double roll); void mergeMask(const std::vector &); + void mergeMask(const std::vector &); struct OutputData { diff --git a/dynamic_vino_lib/src/inferences/object_segmentation_maskrcnn.cpp b/dynamic_vino_lib/src/inferences/object_segmentation_maskrcnn.cpp index 0426f1cf..2858d42a 100644 --- a/dynamic_vino_lib/src/inferences/object_segmentation_maskrcnn.cpp +++ b/dynamic_vino_lib/src/inferences/object_segmentation_maskrcnn.cpp @@ -130,7 +130,6 @@ bool dynamic_vino_lib::ObjectSegmentationMaskrcnn::fetchResults() //get detection data ov::Tensor do_tensor = infer_request.get_tensor(detection_output.c_str()); const auto do_data = do_tensor.data(); - slog::debug << "11111111111" << do_data << slog::endl; ov::Shape do_shape = do_tensor.get_shape(); slog::debug << "Detection Blob getDims = " <(box_info[0]); slog::debug << "batch =" << batch << slog::endl; if (batch < 0) { diff --git a/dynamic_vino_lib/src/models/object_segmentation_model.cpp b/dynamic_vino_lib/src/models/object_segmentation_model.cpp index bc5bc2e7..a152c99e 100644 --- a/dynamic_vino_lib/src/models/object_segmentation_model.cpp +++ b/dynamic_vino_lib/src/models/object_segmentation_model.cpp @@ -110,7 +110,7 @@ bool Models::ObjectSegmentationModel::updateLayerProperty( std::shared_ptr& model) { slog::info<< "Checking INPUTS for Model" <inputs(); slog::debug<<"input size"< & 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] % colors_.size() ]; + 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(), + cv::Scalar(color[2], color[1], color[0]) ); + roi_img.copyTo(colored_mask, mask <= MASK_THRESHOLD); + cv::addWeighted(colored_mask, alpha, roi_img, 1.0f - alpha, 0.0f, roi_img); + } +} +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; + auto fd_conf = results[i].getConfidence(); + if (fd_conf >= 0) { + std::ostringstream ostream; + ostream << "[" << std::fixed << std::setprecision(3) << fd_conf << "]"; + outputs_[target_index].desc += ostream.str(); + } + auto label = results[i].getLabel(); + outputs_[target_index].desc += "[" + label + "]"; + } + mergeMask(results); +} + + + + void Outputs::ImageWindowOutput::accept( const std::vector & results) { diff --git a/dynamic_vino_lib/src/pipeline_manager.cpp b/dynamic_vino_lib/src/pipeline_manager.cpp index 96941a8b..172a1f45 100644 --- a/dynamic_vino_lib/src/pipeline_manager.cpp +++ b/dynamic_vino_lib/src/pipeline_manager.cpp @@ -336,12 +336,12 @@ std::shared_ptr PipelineManager::createObjectSegmentationMaskrcnn(const Params::ParamManager::InferenceRawData & infer) { auto model = - std::make_shared(infer.label, infer.model, infer.batch); + std::make_shared(infer.label, infer.model, infer.batch); model->modelInit(); slog::info << "Segmentation model initialized." << slog::endl; auto engine = engine_manager_.createEngine(infer.engine, model); slog::info << "Segmentation Engine initialized." << slog::endl; - auto segmentation_inference_ptr = std::make_shared( + auto segmentation_inference_ptr = std::make_shared( infer.confidence_threshold); slog::info << "Segmentation Inference instanced." << slog::endl; segmentation_inference_ptr->loadNetwork(model); From f7878dda2e174e4e4d7aecc63b3b58c90e27e3c5 Mon Sep 17 00:00:00 2001 From: wujiawei Date: Tue, 29 Nov 2022 13:17:58 +0800 Subject: [PATCH 6/6] fix segmentation pipeline --- dynamic_vino_lib/src/inferences/object_segmentation.cpp | 7 ------- dynamic_vino_lib/src/models/object_segmentation_model.cpp | 1 - 2 files changed, 8 deletions(-) diff --git a/dynamic_vino_lib/src/inferences/object_segmentation.cpp b/dynamic_vino_lib/src/inferences/object_segmentation.cpp index a891b401..ba2a5610 100644 --- a/dynamic_vino_lib/src/inferences/object_segmentation.cpp +++ b/dynamic_vino_lib/src/inferences/object_segmentation.cpp @@ -123,13 +123,10 @@ bool dynamic_vino_lib::ObjectSegmentation::fetchResults() ov::InferRequest infer_request = getEngine()->getRequest(); slog::debug << "Analyzing Detection results..." << slog::endl; std::string detection_output = valid_model_->getOutputName("detection"); - std::string mask_output = valid_model_->getOutputName("masks"); ov::Tensor output_tensor = infer_request.get_tensor(detection_output); const auto out_data = output_tensor.data(); ov::Shape out_shape = output_tensor.get_shape(); - ov::Tensor masks_tensor = infer_request.get_tensor(detection_output.c_str()); - const auto masks_data = masks_tensor.data(); size_t output_w, output_h, output_des, output_extra = 0; if (out_shape.size() == 3) { output_w = out_shape[2]; @@ -236,9 +233,5 @@ const std::vector dynamic_vino_lib::ObjectSegmentation::getFilteredROI << "Filter conditions: " << filter_conditions << slog::endl; } std::vector filtered_rois; - for (auto res : results_) - { - filtered_rois.push_back(res.getLocation()); - } return filtered_rois; } diff --git a/dynamic_vino_lib/src/models/object_segmentation_model.cpp b/dynamic_vino_lib/src/models/object_segmentation_model.cpp index a152c99e..1d99ec11 100644 --- a/dynamic_vino_lib/src/models/object_segmentation_model.cpp +++ b/dynamic_vino_lib/src/models/object_segmentation_model.cpp @@ -193,7 +193,6 @@ bool Models::ObjectSegmentationModel::updateLayerProperty( slog::debug << "output HEIGHT " << outHeight<< slog::endl; slog::debug << "output CHANNELS " << outChannels<< slog::endl; slog::debug << "output NAME " << output_tensor_name_<< slog::endl; - addOutputInfo("masks", output_tensor_name_); addOutputInfo("detection", output_tensor_name_); printAttribute();