Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 2 additions & 0 deletions dynamic_vino_lib/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -208,6 +209,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
Expand Down
Original file line number Diff line number Diff line change
@@ -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_MASKRCNN_HPP_
#define DYNAMIC_VINO_LIB__INFERENCES__OBJECT_SEGMENTATION_MASKRCNN_HPP_
#include <object_msgs/msg/object.hpp>
#include <object_msgs/msg/object_in_box.hpp>
#include <object_msgs/msg/objects_in_boxes.hpp>
#include <rclcpp/rclcpp.hpp>
#include <memory>
#include <vector>
#include <string>
#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 ObjectSegmentationMaskrcnnResult
* @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<Models::ObjectSegmentationMaskrcnnModel>);
/**
* @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<Outputs::BaseOutput> & 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<cv::Rect> getFilteredROIs(
const std::string filter_conditions) const override;

private:
std::shared_ptr<Models::ObjectSegmentationMaskrcnnModel> valid_model_;
std::vector<Result> results_;
int width_ = 0;
int height_ = 0;
double show_output_thresh_ = 0;

std::vector<cv::Vec3b> 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_
Original file line number Diff line number Diff line change
@@ -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 <string>
#include <openvino/openvino.hpp>
#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<Engines::Engine> & ,const cv::Mat &,
const cv::Rect & ) override;

bool matToBlob(
const cv::Mat & , const cv::Rect &, float ,
int , const std::shared_ptr<Engines::Engine> & );

/**
* @brief Get the name of this segmentation model.
* @return Name of the model.
*/
const std::string getModelCategory() const override;
bool updateLayerProperty(std::shared_ptr<ov::Model>&) override;

private:
int max_proposal_count_;
int object_size_;
};
} // namespace Models
#endif // DYNAMIC_VINO_LIB__MODELS__OBJECT_SEGMENTATION_MASKRCNN_MODEL_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -108,6 +109,12 @@ class BaseOutput
virtual void accept(const std::vector<dynamic_vino_lib::ObjectSegmentationResult> &)
{
}
/**
* @brief Generate output content according to the object segmentation maskrcnn result.
*/
virtual void accept(const std::vector<dynamic_vino_lib::ObjectSegmentationMaskrcnnResult> &)
{
}
/**
* @brief Generate output content according to the object detection result.
*/
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -98,6 +98,12 @@ class ImageWindowOutput : public BaseOutput
* @param[in] An obejct segmentation result objetc.
*/
void accept(const std::vector<dynamic_vino_lib::ObjectSegmentationResult> &) 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<dynamic_vino_lib::ObjectSegmentationMaskrcnnResult> &) override;
/**
* @brief Generate image window output content according to
* the face detection result.
Expand Down Expand Up @@ -145,6 +151,7 @@ class ImageWindowOutput : public BaseOutput
cv::Mat getRotationTransform(double yaw, double pitch, double roll);

void mergeMask(const std::vector<dynamic_vino_lib::ObjectSegmentationResult> &);
void mergeMask(const std::vector<dynamic_vino_lib::ObjectSegmentationMaskrcnnResult> &);

struct OutputData
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -114,6 +114,12 @@ class RosTopicOutput : public BaseOutput
* @param[in] results a bundle of object segmentation results.
*/
void accept(const std::vector<dynamic_vino_lib::ObjectSegmentationResult> &) 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<dynamic_vino_lib::ObjectSegmentationMaskrcnnResult> &) override;
/**
* @brief Generate ros topic infomation according to
* the object detection result.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -91,6 +91,12 @@ class RvizOutput : public BaseOutput
* @param[in] results A bundle of object segmentation results.
*/
void accept(const std::vector<dynamic_vino_lib::ObjectSegmentationResult> &) 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<dynamic_vino_lib::ObjectSegmentationMaskrcnnResult> &) override;
/**
* @brief Generate rviz output content according to
* the emotion detection result.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -125,6 +125,8 @@ class PipelineManager
std::shared_ptr<dynamic_vino_lib::BaseInference>
createObjectSegmentation(const Params::ParamManager::InferenceRawData & infer);
std::shared_ptr<dynamic_vino_lib::BaseInference>
createObjectSegmentationMaskrcnn(const Params::ParamManager::InferenceRawData & infer);
std::shared_ptr<dynamic_vino_lib::BaseInference>
createPersonReidentification(const Params::ParamManager::InferenceRawData & infer);
std::shared_ptr<dynamic_vino_lib::BaseInference>
createPersonAttribsDetection(const Params::ParamManager::InferenceRawData & infer);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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";
Expand Down
7 changes: 0 additions & 7 deletions dynamic_vino_lib/src/inferences/object_segmentation.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<float>();
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<float>();
size_t output_w, output_h, output_des, output_extra = 0;
if (out_shape.size() == 3) {
output_w = out_shape[2];
Expand Down Expand Up @@ -236,9 +233,5 @@ const std::vector<cv::Rect> dynamic_vino_lib::ObjectSegmentation::getFilteredROI
<< "Filter conditions: " << filter_conditions << slog::endl;
}
std::vector<cv::Rect> filtered_rois;
for (auto res : results_)
{
filtered_rois.push_back(res.getLocation());
}
return filtered_rois;
}
Loading