From 822e62a80b1a9c96febf307d5d9a5171865f2976 Mon Sep 17 00:00:00 2001 From: Anthony Tarbinian <42757207+atar13@users.noreply.github.com> Date: Tue, 11 Jun 2024 22:21:48 -0700 Subject: [PATCH] saliency testing (#201) added benchmarking for saliency and matching --------- Co-authored-by: Samir Rashid Co-authored-by: Triton UAS Co-authored-by: Igor Aprelev --- docker/Makefile | 1 - docker/jetson-pixhawk-compose.yml | 2 +- src/cv/CMakeLists.txt | 1 + src/cv/saliency.cpp | 8 +++++++- tests/integration/cv_matching.cpp | 10 ++++++++++ tests/integration/cv_saliency.cpp | 11 +++++++++++ 6 files changed, 30 insertions(+), 3 deletions(-) diff --git a/docker/Makefile b/docker/Makefile index cfebd610..257cce19 100644 --- a/docker/Makefile +++ b/docker/Makefile @@ -29,7 +29,6 @@ stop-jetson-pixhawk-compose: run-jetson-cuda-check: docker run -it --rm --runtime nvidia -i ghcr.io/tritonuas/obcpp:jetson /obcpp/build/bin/cuda_check - # NOTE: Use this target for development where you want to quicly edit source code and recompile. # This will spawn up the jetson container, launch you into a bash shell and mount the # host's obcpp directory at "/obcpp" in the container. This means you can edit the source diff --git a/docker/jetson-pixhawk-compose.yml b/docker/jetson-pixhawk-compose.yml index 1fe2e47d..a62306f5 100644 --- a/docker/jetson-pixhawk-compose.yml +++ b/docker/jetson-pixhawk-compose.yml @@ -1,7 +1,7 @@ version: "3" services: obcpp: - image: tritonuas/obcpp:jetson + image: ghcr.io/tritonuas/obcpp:jetson runtime: nvidia network_mode: "host" devices: diff --git a/src/cv/CMakeLists.txt b/src/cv/CMakeLists.txt index d0fd517a..4d74106f 100644 --- a/src/cv/CMakeLists.txt +++ b/src/cv/CMakeLists.txt @@ -14,6 +14,7 @@ set(FILES set(LIB_DEPS obcpp_protos obcpp_utilities + obcpp_camera ) add_library(${LIB_NAME} STATIC diff --git a/src/cv/saliency.cpp b/src/cv/saliency.cpp index b57d0969..3b494fd9 100644 --- a/src/cv/saliency.cpp +++ b/src/cv/saliency.cpp @@ -7,6 +7,7 @@ #include #include "utilities/logging.hpp" + #define REGULAR_TARGET 1 #define MANNIKIN 2 @@ -34,7 +35,12 @@ std::vector Saliency::salience(cv::Mat image) { tensor = tensor.toType(c10::kFloat).div(255); // swap axis tensor = Saliency::transpose(tensor, { (2), (0), (1) }); - auto input_to_net = ToInput(tensor); + + // eventually add device as member of Saliency + c10::Device device = torch::cuda::is_available() ? torch::kCUDA : torch::kCPU; + auto tensor_cuda = tensor.to(device); + + auto input_to_net = ToInput(tensor_cuda); /* * forward() runs an inference on the input image using the provided model diff --git a/tests/integration/cv_matching.cpp b/tests/integration/cv_matching.cpp index c9554c5d..95501366 100644 --- a/tests/integration/cv_matching.cpp +++ b/tests/integration/cv_matching.cpp @@ -7,6 +7,7 @@ #include "cv/matching.hpp" #include "utilities/constants.hpp" +#include "utilities/common.hpp" // Download these test images by running "make pull_matching_test_images" or from the test.zip here https://drive.google.com/drive/u/1/folders/1opXBWx6bBF7J3-JSFtrhfFIkYis9qhGR // Or, any cropped not-stolen images will work @@ -79,7 +80,10 @@ int main(int argc, char* argv[]) { cv::Mat ref4 = cv::imread(refImagePath4); referenceImages.push_back(std::make_pair(ref4, BottleDropIndex(1))); + auto startLoad = getUnixTime_ms().count(); Matching matcher(bottlesToDrop, referenceImages, modelPath); + auto endLoad = getUnixTime_ms().count(); + LOG_F(INFO, "time to load: %lu milliseconds", endLoad - startLoad); cv::Mat image = cv::imread(imageMatchPath); Bbox dummyBox(0, 0, 0, 0); CroppedTarget cropped = { @@ -95,15 +99,21 @@ int main(int argc, char* argv[]) { false }; + auto startMatch = getUnixTime_ms().count(); MatchResult result = matcher.match(cropped); + auto endMatch = getUnixTime_ms().count(); LOG_F(INFO, "\nTRUE MATCH TEST:\nClosest is bottle at index %d\nThe similarity is %.3f\n", int(result.bottleDropIndex), result.distance); + auto startMatchFalse = getUnixTime_ms().count(); MatchResult resultFalse = matcher.match(croppedFalse); + auto endMatchFalse = getUnixTime_ms().count(); LOG_F(INFO, "\nFALSE MATCH TEST:\nClosest is bottle at index %d\nThe similarity is %.3f\n", int(resultFalse.bottleDropIndex), resultFalse.distance); + LOG_F(INFO, "time to match: %lu milliseconds", + (endMatch - startMatch + endMatchFalse - startMatchFalse)/2); return 0; } \ No newline at end of file diff --git a/tests/integration/cv_saliency.cpp b/tests/integration/cv_saliency.cpp index 59822d12..3366e252 100644 --- a/tests/integration/cv_saliency.cpp +++ b/tests/integration/cv_saliency.cpp @@ -5,22 +5,32 @@ #include #include "cv/saliency.hpp" +#include "utilities/common.hpp" #include "loguru.hpp" // expected arguments: int main(int argc, const char* argv[]) { + if (argc != 3) { std::cerr << "usage: example-app \n"; return -1; } // convert image to tensor + const char* modelPath = argv[1]; + auto startLoad = getUnixTime_ms().count(); Saliency sal(modelPath); + auto endLoad = getUnixTime_ms().count(); + LOG_F(INFO, "time to load: %u milliseconds", endLoad - startLoad); + const char* imgPath = argv[2]; cv::Mat img = cv::imread(imgPath, cv::IMREAD_COLOR); + auto startSalience = getUnixTime_ms().count(); std::vector predictions = sal.salience(img); + auto endSalience = getUnixTime_ms().count(); + LOG_F(INFO, "time to saliency: %u milliseconds", endSalience - startSalience); img = cv::imread(imgPath, cv::IMREAD_COLOR); @@ -36,6 +46,7 @@ int main(int argc, const char* argv[]) { // cv::namedWindow("cropped targets", cv::WINDOW_FULLSCREEN); // cv::imshow("cropped targets", img); // cv::waitKey(0); + cv::imwrite("croppedTargets.jpg", img); LOG_F(INFO, "saved croppedTargets.jpg to build/"); // testing: save input image to file path (cv::imsave?) with bounding boxes overlayed