diff --git a/perception/object_detector/object_detector.cpp b/perception/object_detector/object_detector.cpp index 601b03a1..69025af3 100644 --- a/perception/object_detector/object_detector.cpp +++ b/perception/object_detector/object_detector.cpp @@ -32,7 +32,7 @@ namespace mrover { using namespace std::placeholders; - mModel = Model(modelName, {0, 0}, {"bottle", "hammer"}, mTensorRT.getInputTensorSize(), mTensorRT.getOutputTensorSize(), [](Model const& model, cv::Mat& rgbImage, cv::Mat& blobSizedImage, cv::Mat& blob){preprocessYOLOv8Input(model, rgbImage, blobSizedImage, blob);}, [this](Model const& model, cv::Mat& output, std::vector& detections){parseYOLOv8Output(model, output, detections);}); + mModel = Model(modelName, {0, 0}, {"bottle", "hammer"}, mTensorRT.getInputTensorSize(), mTensorRT.getOutputTensorSize(), [](Model const& model, cv::Mat& rgbImage, cv::Mat& blobSizedImage, cv::Mat& blob) { preprocessYOLOv8Input(model, rgbImage, blobSizedImage, blob); }, [this](Model const& model, cv::Mat& output, std::vector& detections) { parseYOLOv8Output(model, output, detections); }); RCLCPP_INFO_STREAM(get_logger(), std::format("Object detector initialized with model: {} and thresholds: {} and {}", mModel.modelName, mModelScoreThreshold, mModelNMSThreshold)); } diff --git a/perception/object_detector/object_detector.hpp b/perception/object_detector/object_detector.hpp index e8e92f63..ea0ac708 100644 --- a/perception/object_detector/object_detector.hpp +++ b/perception/object_detector/object_detector.hpp @@ -12,7 +12,7 @@ namespace mrover { float confidence{}; cv::Rect box; - Detection(int _classId, std::string _className, float _confidence, cv::Rect _box) : classId{_classId}, className{_className}, confidence{_confidence}, box{_box}{} + Detection(int _classId, std::string _className, float _confidence, cv::Rect _box) : classId{_classId}, className{_className}, confidence{_confidence}, box{_box} {} }; struct Model { @@ -37,7 +37,6 @@ namespace mrover { Model(std::string _modelName, std::vector _objectHitCounts, std::vector _classes, std::vector _inputTensorSize, std::vector _outputTensorSize, std::function _rbgImageToBlob, std::function&)> _outputTensorToDetections) : modelName{std::move(_modelName)}, objectHitCounts(std::move(_objectHitCounts)), classes(std::move(_classes)), inputTensorSize(std::move(_inputTensorSize)), outputTensorSize(std::move(_outputTensorSize)), rgbImageToBlob{std::move(_rbgImageToBlob)}, outputTensorToDetections{std::move(_outputTensorToDetections)} {} }; - static constexpr char const* NODE_NAME = "object_detector"; @@ -78,10 +77,10 @@ namespace mrover { auto publishDetectedObjects(cv::InputArray const& image) -> void; static auto drawDetectionBoxes(cv::InputOutputArray& image, std::span detections) -> void; - + auto parseYOLOv8Output(Model const& model, - cv::Mat& output, - std::vector& detections) const -> void; + cv::Mat& output, + std::vector& detections) const -> void; static auto preprocessYOLOv8Input(Model const& model, cv::Mat const& rgbImage, cv::Mat& blobSizedImage, cv::Mat& blob) -> void;