Skip to content

Commit

Permalink
0.2.0 - Minor (#52)
Browse files Browse the repository at this point in the history
* 📖 Included initial TODOs within code. Starting dev for v0.2.1.

Signed-off-by: Bey Hao Yun <beyhy94@gmail.com>

* 🔨 Included experimental abstracted visualization workflow. Removed debug statement from epd_container.cpp.

Signed-off-by: Bey Hao Yun <beyhy94@gmail.com>

* 🔥 🔨 Removed completed TODOs for Precision Level 3 Visualize workflow. Modified for common infer_action function call for specified workflow.

Signed-off-by: Bey Hao Yun <beyhy94@gmail.com>

* 🔨 Rectified curLabel display in P3 Visualize Workflow.

Signed-off-by: Bey Hao Yun <beyhy94@gmail.com>

* 🔨 Transferred experimental visualize function from EasyPerceptionDeployment to EPDContainer class for better unit testing coverage.

Signed-off-by: Bey Hao Yun <beyhy94@gmail.com>

* 🔥 Removed deprecated infer_visualize. Code verbosity reduced drastically.

Signed-off-by: Bey Hao Yun <beyhy94@gmail.com>

* 🔨 Renamed infer_action for P3 U1 Visualize workflow to just infer.

Signed-off-by: Bey Hao Yun <beyhy94@gmail.com>

* 🔨 Surfaced usecase_config activateUseCase function call to level of rclcpp::Node callback, EasyPerceptionDeployment. Ready for optimization in P3 U1 Visualize and Action Workflow.

Signed-off-by: Bey Hao Yun <beyhy94@gmail.com>

* 🔨 Combined infer_action and infer_visualize for P2 U0 Visualize workflow. Modified EPDContainer visualize function to accept both P2 and P3 model detection outputs.

Signed-off-by: Bey Hao Yun <beyhy94@gmail.com>

* 🔥 🔨 Removed deprecated infer_visualize-concerned functions within P2 workflow.

Signed-off-by: Bey Hao Yun <beyhy94@gmail.com>

* 🔥 Removed P2-specific activateUseCase, count and matchColor function calls. Generified usecase_config functions to adapt to both P2 and P3 model detection outputs. Verified with successfull local build.

Signed-off-by: Bey Hao Yun <beyhy94@gmail.com>

* 🔨 Changed all instantiation of bboxes from data type float to int to silence intrinsic warnings for better debugging.

Signed-off-by: Bey Hao Yun <beyhy94@gmail.com>

* 🔨 Corrected assignment of output_obj instead of result in P2 image callback. Added CHANGELOG.rst.

Signed-off-by: Bey Hao Yun <beyhy94@gmail.com>

* 🔨 Attempted fix for failing CI build.

Signed-off-by: Bey Hao Yun <beyhy94@gmail.com>

* 🔨 Adhered to ROS2 REP-2004 linting standards.

Signed-off-by: Bey Hao Yun <beyhy94@gmail.com>

* 📖 Updated copyright year to current.

Signed-off-by: Bey Hao Yun <beyhy94@gmail.com>

* 🔨 Expanding EPD::activateUseCase for optimization. Yet to verify.

Signed-off-by: Bey Hao Yun <beyhy94@gmail.com>

* 🔨 Removed all instances of inefficient .json file reading within usecase_config.hpp. Code verbosity reduced as well.

Signed-off-by: Bey Hao Yun <beyhy94@gmail.com>

* 🔨 Replace infer_visualize call with infer_action for Tracking Visualize workflow. Verified with successful build and manual testing.n

Signed-off-by: Bey Hao Yun <beyhy94@gmail.com>

* 🔨 Renamed infer_action in P2 workflows to infer.

Signed-off-by: Bey Hao Yun <beyhy94@gmail.com>

* 🔥 🔨 Removed deprecated infer_visualize from Tracking workflow. Renamed infer_action to generic infer for same Tracking workflow.

Signed-off-by: Bey Hao Yun <beyhy94@gmail.com>

* 🔨 Verified replaced of infer_visualize with infer_action within Localization workflow.

Signed-off-by: Bey Hao Yun <beyhy94@gmail.com>

* 🔨 Renamed infer_action to infer for Localization workflow. Codestructuring completed.

Signed-off-by: Bey Hao Yun <beyhy94@gmail.com>

* 🔨 Adhered codebase to REP-2004 linting standards.

Signed-off-by: Bey Hao Yun <beyhy94@gmail.com>

* 🔨 Updated default session_config.json and input_image_topic.json.

Signed-off-by: Bey Hao Yun <beyhy94@gmail.com>

* 📖 🔨 Rectified CHANGELOG.rst for 0.2.0 - Minor release.

Signed-off-by: Bey Hao Yun <beyhy94@gmail.com>
  • Loading branch information
cardboardcode authored Aug 4, 2022
1 parent d0b6ceb commit 19673a9
Show file tree
Hide file tree
Showing 48 changed files with 511 additions and 1,491 deletions.
14 changes: 14 additions & 0 deletions easy_perception_deployment/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -21,3 +21,17 @@ Changelog for package easy_perception_deployment
* Updated generateCountClassNames() in usecase_config.hpp to json parsing.
* Fixed wrong if conditions for parsing incoming Use Case integer in Deploy.py.
* Contributor(s): Bey Hao Yun

0.2.0 (2022-08-05)
-------------------
* Removed all instances of infer_visualizes from P2OrtBase and P3OrtBase classes.
* Modified Visualize workflows for all Precision Levels and Use Case configuration to use infer_action.
* Renamed all instances of infer_action to infer.
* Removed debug statement printing onnx_model_path from epd_container.cpp.
* Transferred detection results visualization from P2OrtBase and P3OrtBase to EPDContainer class.
* Generified detection results visualization functions to minimize code verbosity.
* Modified default session_config.json.
* Modified default input_image_topic.json.
* Updated unit testing modules under test folder to reflect new infer function calls for P1OrtBase, P2OrtBase and P3OrtBase classes.
* Contributor(s): Bey Hao Yun

4 changes: 2 additions & 2 deletions easy_perception_deployment/config/input_image_topic.json
Original file line number Diff line number Diff line change
@@ -1,3 +1,3 @@
{
"input_image_topic": "/camera/color/image_raw"
}
"input_image_topic": "/virtual_camera/image_raw"
}
8 changes: 4 additions & 4 deletions easy_perception_deployment/config/session_config.json
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
{
"path_to_label_list" : "/home/cardboardvoice/epd_workspace/5_linting_epd_ws/src/easy_perception_deployment/easy_perception_deployment/data/label_list/imagenet_classes.txt",
"path_to_model" : "/home/cardboardvoice/epd_workspace/5_linting_epd_ws/src/easy_perception_deployment/easy_perception_deployment/data/model/squeezenet1.1-7.onnx",
"path_to_label_list" : "./data/label_list/coco_classes.txt",
"path_to_model" : "./data/model/MaskRCNN-10.onnx",
"useCPU" : "CPU",
"visualizeFlag" : "robot"
}
"visualizeFlag" : "visualize"
}
4 changes: 2 additions & 2 deletions easy_perception_deployment/gui/main.py
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
# Copyright 2020 Advanced Remanufacturing and Technology Centre
# Copyright 2020 ROS-Industrial Consortium Asia Pacific Team
# Copyright 2022 Advanced Remanufacturing and Technology Centre
# Copyright 2022 ROS-Industrial Consortium Asia Pacific Team
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
Expand Down
4 changes: 2 additions & 2 deletions easy_perception_deployment/gui/run_test_gui.bash
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
#!/bin/sh

# Copyright 2020 Advanced Remanufacturing and Technology Centre
# Copyright 2020 ROS-Industrial Consortium Asia Pacific Team
# Copyright 2022 Advanced Remanufacturing and Technology Centre
# Copyright 2022 ROS-Industrial Consortium Asia Pacific Team
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
Expand Down
4 changes: 2 additions & 2 deletions easy_perception_deployment/gui/test_gui.py
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
# Copyright 2020 Advanced Remanufacturing and Technology Centre
# Copyright 2020 ROS-Industrial Consortium Asia Pacific Team
# Copyright 2022 Advanced Remanufacturing and Technology Centre
# Copyright 2022 ROS-Industrial Consortium Asia Pacific Team
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
Expand Down
2 changes: 1 addition & 1 deletion easy_perception_deployment/gui/trainer/P1Trainer.py
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
# Copyright 2020 ROS-Industrial Consortium Asia Pacific
# Copyright 2022 ROS-Industrial Consortium Asia Pacific
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
Expand Down
2 changes: 1 addition & 1 deletion easy_perception_deployment/gui/trainer/P2Trainer.py
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
# Copyright 2020 ROS-Industrial Consortium Asia Pacific
# Copyright 2022 ROS-Industrial Consortium Asia Pacific
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
Expand Down
2 changes: 1 addition & 1 deletion easy_perception_deployment/gui/trainer/P3Trainer.py
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
# Copyright 2020 ROS-Industrial Consortium Asia Pacific
# Copyright 2022 ROS-Industrial Consortium Asia Pacific
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
Expand Down
2 changes: 1 addition & 1 deletion easy_perception_deployment/gui/windows/Counting.py
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
# Copyright 2020 ROS-Industrial Consortium Asia Pacific
# Copyright 2022 ROS-Industrial Consortium Asia Pacific
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
Expand Down
2 changes: 1 addition & 1 deletion easy_perception_deployment/gui/windows/Deploy.py
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
# Copyright 2020 ROS-Industrial Consortium Asia Pacific
# Copyright 2022 ROS-Industrial Consortium Asia Pacific
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
Expand Down
2 changes: 1 addition & 1 deletion easy_perception_deployment/gui/windows/Main.py
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
# Copyright 2020 ROS-Industrial Consortium Asia Pacific
# Copyright 2022 ROS-Industrial Consortium Asia Pacific
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
Expand Down
2 changes: 1 addition & 1 deletion easy_perception_deployment/gui/windows/Tracking.py
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
# Copyright 2020 ROS-Industrial Consortium Asia Pacific
# Copyright 2022 ROS-Industrial Consortium Asia Pacific
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
Expand Down
2 changes: 1 addition & 1 deletion easy_perception_deployment/gui/windows/Train.py
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
# Copyright 2020 ROS-Industrial Consortium Asia Pacific
# Copyright 2022 ROS-Industrial Consortium Asia Pacific
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
// Copyright 2020 Advanced Remanufacturing and Technology Centre
// Copyright 2020 ROS-Industrial Consortium Asia Pacific Team
// Copyright 2022 Advanced Remanufacturing and Technology Centre
// Copyright 2022 ROS-Industrial Consortium Asia Pacific Team
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand Down Expand Up @@ -364,9 +364,31 @@ void EasyPerceptionDeployment::process_localize_callback(
// Initialize timer
std::chrono::high_resolution_clock::time_point begin = std::chrono::high_resolution_clock::now();

EPD::EPDObjectLocalization result = ortAgent_.p3_ort_session->infer(
img,
depth_img,
*camera_info,
camera_to_plane_distance_mm);

cv::Mat resultImg;
if (ortAgent_.isVisualize()) {
resultImg = ortAgent_.p3_ort_session->infer_visualize(img, depth_img, *camera_info);
EPD::EPDObjectTracking converted_result(result.data_size);
converted_result.object_ids.clear();
for (size_t i = 0; i < result.data_size; i++) {
EPD::EPDObjectTracking::LocalizedObject object;
object.name = result.objects[i].name;
object.roi = result.objects[i].roi;
object.mask = result.objects[i].mask;
object.length = result.objects[i].length;
object.breadth = result.objects[i].breadth;
object.height = result.objects[i].height;
object.segmented_pcl = result.objects[i].segmented_pcl;
object.axis = result.objects[i].axis;

converted_result.objects.emplace_back(object);
}

cv::Mat resultImg = ortAgent_.visualize(converted_result, img);

sensor_msgs::msg::Image::SharedPtr output_msg =
cv_bridge::CvImage(std_msgs::msg::Header(), "bgr8", resultImg).toImageMsg();
Expand All @@ -378,12 +400,6 @@ void EasyPerceptionDeployment::process_localize_callback(
RCLCPP_INFO(this->get_logger(), "[-FPS-]= %f\n", 1000.0 / elapsedTime.count());

} else {
EPD::EPDObjectLocalization result = ortAgent_.p3_ort_session->infer_action(
img,
depth_img,
*camera_info,
camera_to_plane_distance_mm);

epd_msgs::msg::EPDObjectLocalization output_msg;

output_msg.header = std_msgs::msg::Header();
Expand Down Expand Up @@ -484,22 +500,19 @@ void EasyPerceptionDeployment::process_tracking_callback(
std::chrono::high_resolution_clock::time_point begin = std::chrono::high_resolution_clock::now();

cv::Mat resultImg;
if (ortAgent_.isVisualize()) {
resultImg = ortAgent_.p3_ort_session->infer_visualize(
img,
depth_img,
*camera_info,
ortAgent_.tracker_type,
ortAgent_.trackers,
ortAgent_.tracker_logs,
ortAgent_.tracker_results);

// DEBUG
// for (size_t i = 0; i < ortAgent_.tracker_results.size(); i++) {
// std::cout << "Tracked Object = [ "
// << ortAgent_.tracker_results[i].obj_tag
// << " ]" << std::endl;
// }
EPD::EPDObjectTracking result = ortAgent_.p3_ort_session->infer(
img,
depth_img,
*camera_info,
camera_to_plane_distance_mm,
ortAgent_.tracker_type,
ortAgent_.trackers,
ortAgent_.tracker_logs,
ortAgent_.tracker_results);

if (ortAgent_.isVisualize()) {
resultImg = ortAgent_.visualize(result, img);

sensor_msgs::msg::Image::SharedPtr output_msg =
cv_bridge::CvImage(std_msgs::msg::Header(), "bgr8", resultImg).toImageMsg();
Expand All @@ -511,16 +524,6 @@ void EasyPerceptionDeployment::process_tracking_callback(
RCLCPP_INFO(this->get_logger(), "[-FPS-]= %f\n", 1000.0 / elapsedTime.count());

} else {
EPD::EPDObjectTracking result = ortAgent_.p3_ort_session->infer_action(
img,
depth_img,
*camera_info,
camera_to_plane_distance_mm,
ortAgent_.tracker_type,
ortAgent_.trackers,
ortAgent_.tracker_logs,
ortAgent_.tracker_results);

epd_msgs::msg::EPDObjectTracking output_msg;

output_msg.header = std_msgs::msg::Header();
Expand All @@ -535,13 +538,6 @@ void EasyPerceptionDeployment::process_tracking_callback(
output_msg.ppy = camera_info->k.at(5);
output_msg.fy = camera_info->k.at(4);

// DEBUG
// std::cout << "[ ";
// for (size_t i = 0; i < output_msg.object_ids.size(); i++) {
// std::cout << " " << output_msg.object_ids[i] << " ";
// }
// std::cout << " ]" << std::endl;

// Populate output_msg objects and roi_array
for (size_t i = 0; i < result.data_size; i++) {
epd_msgs::msg::LocalizedObject object;
Expand Down Expand Up @@ -629,24 +625,40 @@ const
}
case 2:
{
EPD::EPDObjectDetection result = ortAgent_.p2_ort_session->infer(img);
EPD::activateUseCase(
img,
result.bboxes,
result.classIndices,
result.scores,
result.masks,
ortAgent_.classNames,
ortAgent_.useCaseMode,
ortAgent_.countClassNames,
ortAgent_.template_color_path);

EPD::EPDObjectDetection output_obj(result.bboxes.size());
output_obj.bboxes = result.bboxes;
output_obj.classIndices = result.classIndices;
output_obj.scores = result.scores;

if (ortAgent_.isVisualize()) {
resultImg = ortAgent_.p2_ort_session->infer_visualize(img);
resultImg = ortAgent_.visualize(output_obj, img);
sensor_msgs::msg::Image::SharedPtr output_msg =
cv_bridge::CvImage(std_msgs::msg::Header(), "bgr8", resultImg).toImageMsg();
visual_pub->publish(*output_msg);
} else {
EPD::EPDObjectDetection result = ortAgent_.p2_ort_session->infer_action(img);
epd_msgs::msg::EPDObjectDetection output_msg;
for (size_t i = 0; i < result.data_size; i++) {
output_msg.class_indices.push_back(result.classIndices[i]);
for (size_t i = 0; i < output_obj.data_size; i++) {
output_msg.class_indices.push_back(output_obj.classIndices[i]);

output_msg.scores.push_back(result.scores[i]);
output_msg.scores.push_back(output_obj.scores[i]);

sensor_msgs::msg::RegionOfInterest roi;
roi.x_offset = result.bboxes[i][0];
roi.y_offset = result.bboxes[i][1];
roi.width = result.bboxes[i][2] - result.bboxes[i][0];
roi.height = result.bboxes[i][3] - result.bboxes[i][1];
roi.x_offset = output_obj.bboxes[i][0];
roi.y_offset = output_obj.bboxes[i][1];
roi.width = output_obj.bboxes[i][2] - output_obj.bboxes[i][0];
roi.height = output_obj.bboxes[i][3] - output_obj.bboxes[i][1];
roi.do_rectify = false;
output_msg.bboxes.push_back(roi);
}
Expand All @@ -657,29 +669,49 @@ const
}
case 3:
{
EPD::EPDObjectDetection result = ortAgent_.p3_ort_session->infer(img);
EPD::activateUseCase(
img,
result.bboxes,
result.classIndices,
result.scores,
result.masks,
ortAgent_.classNames,
ortAgent_.useCaseMode,
ortAgent_.countClassNames,
ortAgent_.template_color_path);

EPD::EPDObjectDetection output_obj(result.bboxes.size());
output_obj.bboxes = result.bboxes;
output_obj.classIndices = result.classIndices;
output_obj.scores = result.scores;
output_obj.masks = result.masks;

if (ortAgent_.isVisualize()) {
resultImg = ortAgent_.p3_ort_session->infer_visualize(img);
resultImg = ortAgent_.visualize(output_obj, img);
sensor_msgs::msg::Image::SharedPtr output_msg =
cv_bridge::CvImage(std_msgs::msg::Header(), "bgr8", resultImg).toImageMsg();
visual_pub->publish(*output_msg);
} else {
EPD::EPDObjectDetection result = ortAgent_.p3_ort_session->infer_action(img);
epd_msgs::msg::EPDObjectDetection output_msg;
for (size_t i = 0; i < result.data_size; i++) {
output_msg.class_indices.push_back(result.classIndices[i]);
for (size_t i = 0; i < output_obj.data_size; i++) {
output_msg.class_indices.push_back(output_obj.classIndices[i]);

output_msg.scores.push_back(result.scores[i]);
output_msg.scores.push_back(output_obj.scores[i]);

sensor_msgs::msg::RegionOfInterest roi;
roi.x_offset = result.bboxes[i][0];
roi.y_offset = result.bboxes[i][1];
roi.width = result.bboxes[i][2] - result.bboxes[i][0];
roi.height = result.bboxes[i][3] - result.bboxes[i][1];
roi.x_offset = output_obj.bboxes[i][0];
roi.y_offset = output_obj.bboxes[i][1];
roi.width = output_obj.bboxes[i][2] - output_obj.bboxes[i][0];
roi.height = output_obj.bboxes[i][3] - output_obj.bboxes[i][1];
roi.do_rectify = false;
output_msg.bboxes.push_back(roi);

sensor_msgs::msg::Image::SharedPtr mask =
cv_bridge::CvImage(std_msgs::msg::Header(), "32FC1", result.masks[i]).toImageMsg();
cv_bridge::CvImage(
std_msgs::msg::Header(),
"32FC1",
output_obj.masks[i]).toImageMsg();
output_msg.masks.push_back(*mask);
}
p3_pub->publish(output_msg);
Expand Down
Loading

0 comments on commit 19673a9

Please sign in to comment.