Skip to content

Commit

Permalink
Update to OpenVino 2021.4
Browse files Browse the repository at this point in the history
  • Loading branch information
ajtudela committed Dec 13, 2022
1 parent 6220d78 commit 4441d8a
Show file tree
Hide file tree
Showing 5 changed files with 46 additions and 69 deletions.
3 changes: 2 additions & 1 deletion CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,9 +2,10 @@
Changelog for package object_detection_openvino
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

4.0.0 (12-12-2022)
4.0.0 (13-12-2022)
------------------
* First ROS2 (Galactic) version.
* Update to OpenVino 2021.4.

3.2.2 (26-05-2022)
------------------
Expand Down
7 changes: 2 additions & 5 deletions include/object_detection_openvino/objectDetectionVPU.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -157,11 +157,8 @@ class ObjectDetectionVPU : public rclcpp::Node{
/// Topic of the detected objects in 3 dimensions.
std::string detections_3d_topic_;

/// Next image to be processed.
cv::Mat next_frame_;

/// Curent image to be processed.
cv::Mat current_frame_;
/// Image to be processed.
cv::Mat frame_;

/// Class labels of the neural network.
std::vector<std::string> labels_;
Expand Down
27 changes: 9 additions & 18 deletions include/object_detection_openvino/openvino.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -79,22 +79,16 @@ class Openvino{
void load_model_to_device(std::string device);

/**
* @brief Create an asynchronous inference request.
* @brief Create an inference request.
*
*/
void create_async_infer_request();
void create_infer_request();

/**
* @brief Start the asynchronous inference request in the next frame.
* @brief Start an inference request.
*
*/
void start_next_async_infer_request();

/**
* @brief Swap the asynchronous inference request between the current frame and the next one.
*
*/
void swap_async_infer_request();
void start_infer_request();

/**
* @brief Check if the device is ready.
Expand Down Expand Up @@ -126,12 +120,12 @@ class Openvino{
float iou_threshold);

/**
* @brief Convert the frame to an asynchronous inference request.
* @brief Convert the frame to an inference request.
*
* @param frame The frame to be converted.
* @param auto_resize Value to change the size of the frame.
*/
void frame_to_next_infer(const cv::Mat &frame, bool auto_resize = false);
void frame_to_infer(const cv::Mat &frame, bool auto_resize = false);

private:

Expand All @@ -153,11 +147,8 @@ class Openvino{
/// Interface of an executable network.
InferenceEngine::ExecutableNetwork inf_network_;

/// Interface of asynchronous current infer request.
InferenceEngine::InferRequest::Ptr async_infer_request_current_;

/// Interface of asynchronous next infer request.
InferenceEngine::InferRequest::Ptr async_infer_request_next_;
/// Interface of inference request.
InferenceEngine::InferRequest infer_request_;

/// A collection that contains string as key, and OutputInfo smart pointer as value.
InferenceEngine::OutputsDataMap output_info_;
Expand Down Expand Up @@ -204,7 +195,7 @@ class Openvino{
* @param auto_resize Value to change the size of the frame.
*/
void frame_to_blob(const cv::Mat &frame,
InferenceEngine::InferRequest::Ptr &infer_request,
InferenceEngine::InferRequest &infer_request,
const std::string &input_name, bool auto_resize = false);

/**
Expand Down
29 changes: 12 additions & 17 deletions src/objectDetectionVPU.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -83,8 +83,8 @@ ObjectDetectionVPU::ObjectDetectionVPU(std::string node_name) :
// Load model to the device
openvino_.load_model_to_device(device_target_);

// Create async inference request
openvino_.create_async_infer_request();
// Create inference request
openvino_.create_infer_request();
}

ObjectDetectionVPU::~ObjectDetectionVPU(){
Expand Down Expand Up @@ -212,8 +212,8 @@ void ObjectDetectionVPU::color_point_callback(
const size_t color_width = (size_t) color_image_cv->image.size().width;

// Copy data from image to input blob
next_frame_ = color_image_cv->image.clone();
openvino_.frame_to_next_infer(next_frame_, false);
frame_ = color_image_cv->image.clone();
openvino_.frame_to_infer(frame_, false);

// Transform the pointcloud
sensor_msgs::msg::PointCloud2 local_cloud_pc2;
Expand All @@ -238,7 +238,7 @@ void ObjectDetectionVPU::color_point_callback(
// Load network
// In the truly Async mode we start the NEXT infer request, while waiting for the CURRENT to complete
auto t0 = std::chrono::high_resolution_clock::now();
openvino_.start_next_async_infer_request();
openvino_.start_infer_request();
auto t1 = std::chrono::high_resolution_clock::now();

if (openvino_.is_device_ready()){
Expand All @@ -254,17 +254,17 @@ void ObjectDetectionVPU::color_point_callback(
t0 = std::chrono::high_resolution_clock::now();

std::ostringstream out;
cv::putText(current_frame_, out.str(), cv::Point2f(0, 25), cv::FONT_HERSHEY_TRIPLEX, 0.6, cv::Scalar(0, 255, 0), 1, cv::LINE_AA);
cv::putText(frame_, out.str(), cv::Point2f(0, 25), cv::FONT_HERSHEY_TRIPLEX, 0.6, cv::Scalar(0, 255, 0), 1, cv::LINE_AA);
out.str("");
out << "Wallclock time ";
out << std::fixed << std::setprecision(2) << wall.count() << " ms (" << 1000.f / wall.count() << " fps)";
cv::putText(current_frame_, out.str(), cv::Point2f(0, 50), cv::FONT_HERSHEY_TRIPLEX, 0.6, cv::Scalar(0, 0, 255), 1, cv::LINE_AA);
cv::putText(frame_, out.str(), cv::Point2f(0, 50), cv::FONT_HERSHEY_TRIPLEX, 0.6, cv::Scalar(0, 0, 255), 1, cv::LINE_AA);

out.str("");
out << "Detection time : " << std::fixed << std::setprecision(2) << detection.count()
<< " ms ("
<< 1000.f / detection.count() << " fps)";
cv::putText(current_frame_, out.str(), cv::Point2f(0, 75), cv::FONT_HERSHEY_TRIPLEX, 0.6, cv::Scalar(255, 0, 0), 1, cv::LINE_AA);
cv::putText(frame_, out.str(), cv::Point2f(0, 75), cv::FONT_HERSHEY_TRIPLEX, 0.6, cv::Scalar(255, 0, 0), 1, cv::LINE_AA);
}

// Get detection objects
Expand Down Expand Up @@ -324,15 +324,15 @@ void ObjectDetectionVPU::color_point_callback(
conf << ":" << std::fixed << std::setprecision(3) << confidence;
std::string label_text = (label < this->labels_.size() ? this->labels_[label] : std::string("label #") + std::to_string(label)) + conf.str();
// Rectangles for class
cv::rectangle(current_frame_, cv::Point2f(object.xmin-1, object.ymin), cv::Point2f(object.xmin + 180, object.ymin - 22), cv::Scalar(color_rgb[2], color_rgb[1], color_rgb[0]), cv::FILLED, cv::LINE_AA);
cv::putText(current_frame_, label_text, cv::Point2f(object.xmin, object.ymin - 5), cv::FONT_HERSHEY_COMPLEX_SMALL, 1, cv::Scalar(0, 0, 0), 1.5, cv::LINE_AA);
cv::rectangle(current_frame_, cv::Point2f(object.xmin, object.ymin), cv::Point2f(object.xmax, object.ymax), cv::Scalar(color_rgb[2], color_rgb[1], color_rgb[0]), 4, cv::LINE_AA);
cv::rectangle(frame_, cv::Point2f(object.xmin-1, object.ymin), cv::Point2f(object.xmin + 180, object.ymin - 22), cv::Scalar(color_rgb[2], color_rgb[1], color_rgb[0]), cv::FILLED, cv::LINE_AA);
cv::putText(frame_, label_text, cv::Point2f(object.xmin, object.ymin - 5), cv::FONT_HERSHEY_COMPLEX_SMALL, 1, cv::Scalar(0, 0, 0), 1.5, cv::LINE_AA);
cv::rectangle(frame_, cv::Point2f(object.xmin, object.ymin), cv::Point2f(object.xmax, object.ymax), cv::Scalar(color_rgb[2], color_rgb[1], color_rgb[0]), 4, cv::LINE_AA);

detection_id++;
}

// Publish detections and markers
publish_image(current_frame_);
publish_image(frame_);
if (!objects.empty()){
detections_2d_pub_->publish(detections_2d);
if (use_depth_){
Expand All @@ -341,11 +341,6 @@ void ObjectDetectionVPU::color_point_callback(
}
}
}

// In the truly Async mode we swap the NEXT and CURRENT requests for the next iteration
current_frame_ = next_frame_;
next_frame_ = cv::Mat();
openvino_.swap_async_infer_request();
}

void ObjectDetectionVPU::show_histogram(cv::Mat image, cv::Scalar mean){
Expand Down
49 changes: 21 additions & 28 deletions src/openvino.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,9 +43,12 @@ void Openvino::set_target_device(std::string device){
* by mkldnn, but they can be useful for inferring custom topologies.
**/
core_.AddExtension(std::make_shared<Extensions::Cpu::CpuExtensions>(), "CPU");
}else if (device.find("GPU") != std::string::npos){
core_.SetConfig({{PluginConfigParams::KEY_DUMP_KERNELS, PluginConfigParams::YES}}, "GPU");
}else if (device.find("GPU") != std::string::npos ||
device.find("MYRIAD") != std::string::npos ||
device.find("HDDL") != std::string::npos){
core_.SetConfig({{PluginConfigParams::KEY_DUMP_KERNELS, PluginConfigParams::YES}}, device);
}
RCLCPP_INFO(rclcpp::get_logger(node_name_), "Custom extension loaded for %s", device.c_str());
#endif
}

Expand Down Expand Up @@ -125,20 +128,15 @@ void Openvino::configure_network(std::string network_type){
"Only accepts networks with three (YOLO) or two (tiny-YOLO) outputs");
rclcpp::shutdown();
}

for (auto &output : output_info_){
output.second->setPrecision(InferenceEngine::Precision::FP32);
output.second->setLayout(InferenceEngine::Layout::NCHW);
}
}else if (network_type_ == "SSD"){
if (output_info_.size() != 1){
throw std::logic_error("Openvino: Only accepts networks with one output");
}
}

for (auto &output : output_info_){
output.second->setPrecision(InferenceEngine::Precision::FP32);
output.second->setLayout(InferenceEngine::Layout::NCHW);
}
for (auto &output : output_info_){
output.second->setPrecision(InferenceEngine::Precision::FP32);
output.second->setLayout(InferenceEngine::Layout::NCHW);
}
}

Expand All @@ -147,22 +145,17 @@ void Openvino::load_model_to_device(std::string device){
inf_network_ = core_.LoadNetwork(cnn_network_, device);
}

void Openvino::create_async_infer_request(){
RCLCPP_INFO(rclcpp::get_logger(node_name_), "Create infer request");
async_infer_request_current_ = inf_network_.CreateInferRequestPtr();
async_infer_request_next_ = inf_network_.CreateInferRequestPtr();
}

void Openvino::start_next_async_infer_request(){
async_infer_request_next_->StartAsync();
void Openvino::create_infer_request(){
RCLCPP_INFO(rclcpp::get_logger(node_name_), "Create inference request");
infer_request_ = inf_network_.CreateInferRequest();
}

void Openvino::swap_async_infer_request(){
async_infer_request_current_.swap(async_infer_request_next_);
void Openvino::start_infer_request(){
infer_request_.Infer();
}

bool Openvino::is_device_ready(){
return InferenceEngine::OK == async_infer_request_current_->Wait(InferenceEngine::IInferRequest::WaitMode::RESULT_READY);
return InferenceEngine::OK == infer_request_.Wait(InferenceEngine::IInferRequest::WaitMode::RESULT_READY);
}

std::vector<std::string> Openvino::get_labels(){
Expand All @@ -182,7 +175,7 @@ std::vector<DetectionObject> Openvino::get_detection_objects(size_t height,
std::vector<DetectionObject> objects;
for (auto &output: output_info_){
auto output_name = output.first;
InferenceEngine::Blob::Ptr blob = async_infer_request_current_->GetBlob(output_name);
InferenceEngine::Blob::Ptr blob = infer_request_.GetBlob(output_name);

if (network_type_ == "YOLO"){
parse_yolov3_output(cnn_network_,
Expand Down Expand Up @@ -214,8 +207,8 @@ std::vector<DetectionObject> Openvino::get_detection_objects(size_t height,
return objects;
}

void Openvino::frame_to_next_infer(const cv::Mat &frame, bool auto_resize){
frame_to_blob(frame, async_infer_request_next_, input_name_, auto_resize);
void Openvino::frame_to_infer(const cv::Mat &frame, bool auto_resize){
frame_to_blob(frame, infer_request_, input_name_, auto_resize);
}

int Openvino::entry_index(int side, int lcoords, int lclasses, int location, int entry) {
Expand Down Expand Up @@ -243,14 +236,14 @@ double Openvino::intersection_over_union(const DetectionObject &box_1, const Det
}

void Openvino::frame_to_blob(const cv::Mat &frame,
InferenceEngine::InferRequest::Ptr &infer_request,
InferenceEngine::InferRequest &infer_request,
const std::string &input_name, bool auto_resize){
if (auto_resize){
// Just set input blob containing read image. Resize and layout conversion will be done automatically
infer_request->SetBlob(input_name, wrapMat2Blob(frame));
infer_request_.SetBlob(input_name, wrapMat2Blob(frame));
}else{
// Resize and copy data from the image to the input blob
InferenceEngine::Blob::Ptr frame_blob = infer_request->GetBlob(input_name);
InferenceEngine::Blob::Ptr frame_blob = infer_request.GetBlob(input_name);
matU8ToBlob<uint8_t>(frame, frame_blob);
}
}
Expand Down

0 comments on commit 4441d8a

Please sign in to comment.