From 755f0934b3d0499c03f2acaeda44f63e1ccbcb7e Mon Sep 17 00:00:00 2001 From: jbrhm Date: Wed, 18 Sep 2024 11:30:41 -0400 Subject: [PATCH] Final Refactoring --- perception/object_detector/object_detector.cpp | 2 +- perception/object_detector/object_detector.hpp | 2 +- .../object_detector/object_detector.processing.cpp | 2 +- perception/object_detector/pch.hpp | 2 +- tensorrt/{learning.cpp => tensorrt.cpp} | 12 ++++++------ tensorrt/{learning.hpp => tensorrt.hpp} | 8 ++++---- 6 files changed, 14 insertions(+), 14 deletions(-) rename tensorrt/{learning.cpp => tensorrt.cpp} (86%) rename tensorrt/{learning.hpp => tensorrt.hpp} (85%) diff --git a/perception/object_detector/object_detector.cpp b/perception/object_detector/object_detector.cpp index 7e8962ea..4b9de42a 100644 --- a/perception/object_detector/object_detector.cpp +++ b/perception/object_detector/object_detector.cpp @@ -23,7 +23,7 @@ namespace mrover { RCLCPP_INFO_STREAM(get_logger(), "Opening Model " << mModelName); - mLearning = Learning{mModelName, packagePath}; + mTensorRT = TensortRT{mModelName, packagePath}; mDebugImgPub = create_publisher("object_detector/debug_img", 1); diff --git a/perception/object_detector/object_detector.hpp b/perception/object_detector/object_detector.hpp index 66854466..28ebe502 100644 --- a/perception/object_detector/object_detector.hpp +++ b/perception/object_detector/object_detector.hpp @@ -20,7 +20,7 @@ namespace mrover { LoopProfiler mLoopProfiler; - Learning mLearning; + TensortRT mTensorRT; cv::Mat mRgbImage, mImageBlob; sensor_msgs::msg::Image mDetectionsImageMessage; diff --git a/perception/object_detector/object_detector.processing.cpp b/perception/object_detector/object_detector.processing.cpp index 7ffa678b..ceebc0ec 100644 --- a/perception/object_detector/object_detector.processing.cpp +++ b/perception/object_detector/object_detector.processing.cpp @@ -26,7 +26,7 @@ namespace mrover { // Run the blob through the model std::vector detections{}; - mLearning.modelForwardPass(mImageBlob, detections, mModelScoreThreshold, mModelNmsThreshold); + mTensorRT.modelForwardPass(mImageBlob, detections, mModelScoreThreshold, mModelNmsThreshold); mLoopProfiler.measureEvent("Execution"); diff --git a/perception/object_detector/pch.hpp b/perception/object_detector/pch.hpp index 43e61f29..b056aa17 100644 --- a/perception/object_detector/pch.hpp +++ b/perception/object_detector/pch.hpp @@ -49,4 +49,4 @@ #include "parameter.hpp" #include "point.hpp" -#include +#include diff --git a/tensorrt/learning.cpp b/tensorrt/tensorrt.cpp similarity index 86% rename from tensorrt/learning.cpp rename to tensorrt/tensorrt.cpp index 32c0a522..3d2611b5 100644 --- a/tensorrt/learning.cpp +++ b/tensorrt/tensorrt.cpp @@ -1,10 +1,10 @@ -#include "learning.hpp" +#include "tensorrt.hpp" using namespace std; -Learning::Learning() = default; +TensortRT::TensortRT() = default; -Learning::Learning(string modelName, string& packagePathString) : mModelName{std::move(modelName)} { +TensortRT::TensortRT(string modelName, string& packagePathString) : mModelName{std::move(modelName)} { std::filesystem::path packagePath = packagePathString; std::filesystem::path modelFileName = mModelName.append(".onnx"); @@ -13,15 +13,15 @@ Learning::Learning(string modelName, string& packagePathString) : mModelName{std mInferenceWrapper = InferenceWrapper{modelPath, mModelName, packagePath}; } -Learning::~Learning() = default; +TensortRT::~TensortRT() = default; -auto Learning::modelForwardPass(cv::Mat const& blob, std::vector& detections, float modelScoreThreshold, float modelNMSThreshold) const -> void { +auto TensortRT::modelForwardPass(cv::Mat const& blob, std::vector& detections, float modelScoreThreshold, float modelNMSThreshold) const -> void { mInferenceWrapper.doDetections(blob); cv::Mat output = mInferenceWrapper.getOutputTensor(); parseModelOutput(output, detections, modelScoreThreshold, modelNMSThreshold); } -auto Learning::parseModelOutput(cv::Mat& output, std::vector& detections, float modelScoreThreshold, float modelNMSThreshold) const -> void { +auto TensortRT::parseModelOutput(cv::Mat& output, std::vector& detections, float modelScoreThreshold, float modelNMSThreshold) const -> void { // Parse model specific dimensioning from the output // The input to this function is expecting a YOLOv8 style model, thus the dimensions should be > rows diff --git a/tensorrt/learning.hpp b/tensorrt/tensorrt.hpp similarity index 85% rename from tensorrt/learning.hpp rename to tensorrt/tensorrt.hpp index 8723eca9..2737634a 100644 --- a/tensorrt/learning.hpp +++ b/tensorrt/tensorrt.hpp @@ -9,7 +9,7 @@ struct Detection { cv::Rect box; }; -class Learning { +class TensortRT { std::string mModelName; std::vector classes{"bottle", "hammer"}; @@ -22,11 +22,11 @@ class Learning { float modelNMSThreshold = 0.5) const -> void; public: - Learning(); + TensortRT(); - explicit Learning(std::string modelName, std::string& packagePathString); + explicit TensortRT(std::string modelName, std::string& packagePathString); - ~Learning(); + ~TensortRT(); auto modelForwardPass(cv::Mat const& blob, std::vector& detections,