diff --git a/.gitignore b/.gitignore index 27acc6c2..6b66ac64 100644 --- a/.gitignore +++ b/.gitignore @@ -23,9 +23,6 @@ images/* tests/integration/images/* !tests/integration/images/.gitkeep -!tests/integration/images/saliency/ -!tests/integration/images/saliency/.gitkeep -tests/integration/images/saliency/*.jpg .vscode/* !.vscode/c_cpp_properties.json diff --git a/CMakeLists.txt b/CMakeLists.txt index 7f5f9cc4..2eae0a3e 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -153,35 +153,39 @@ add_custom_target(pull_models # Saliency model add_custom_target(pull_saliency COMMAND gdown 1S1IfXlGs_pCH49DwZmbD-tZA5YH0A1gx -O ${CMAKE_BINARY_DIR}/../models/torchscript_19.pth + USES_TERMINAL ) # Matching model add_custom_target(pull_matching COMMAND gdown 1NeFiAfSSLXAZWlehfd0ox7p_jFF4YdrO -O ${CMAKE_BINARY_DIR}/../models/target_siamese_1.pt + USES_TERMINAL ) # Segmentation model add_custom_target(pull_segmentation COMMAND gdown 1U2EbfJFzcjVnjTuD6ud-bIf8YOiEassf -O ${CMAKE_BINARY_DIR}/../models/fcn-model_20-epochs_06-01-2023T21-16-02.pth + USES_TERMINAL ) # ============================= # ============================= # Pull testing images +add_custom_target(pull_test_images + DEPENDS pull_matching_test_images pull_saliency_test_images +) # pull cropped images from fraternal_targets testing folder add_custom_target(pull_matching_test_images - COMMAND gdown 1opxdXw75jSQZu9s61njE6hjQkfHiKvgp -O ${CMAKE_BINARY_DIR}/../tests/integration/images/test.zip && - mkdir -p ${CMAKE_BINARY_DIR}/../tests/integration/images/matching_cropped && - unzip ${CMAKE_BINARY_DIR}/../tests/integration/images/test.zip -d ${CMAKE_BINARY_DIR}/../tests/integration/images/matching_cropped + COMMAND gdown 1vmP3HUS1SyqhdtJrP4QuFpGbyoyfaYSe --folder -O ${CMAKE_BINARY_DIR}/../tests/integration/images/matching + USES_TERMINAL ) # pull cropped images from saliency images testing folder add_custom_target(pull_saliency_test_images - COMMAND gdown 1HJLdrm0X3VxnlQ3Z58EE9-Y5VX1NlhAz -O ${CMAKE_BINARY_DIR}/../tests/integration/images/saliency.zip && - mkdir -p ${CMAKE_BINARY_DIR}/../tests/integration/images/saliency && - unzip ${CMAKE_BINARY_DIR}/../tests/integration/images/saliency.zip -d ${CMAKE_BINARY_DIR}/../tests/integration/images/saliency + COMMAND gdown 1JvtQUroZJHo51E37_IA2D1mfdJj2smyR --folder -O ${CMAKE_BINARY_DIR}/../tests/integration/images/saliency + USES_TERMINAL ) # ============================= diff --git a/configs/dev-config.json b/configs/dev-config.json index 3edd57c7..ca5ed13d 100644 --- a/configs/dev-config.json +++ b/configs/dev-config.json @@ -49,7 +49,7 @@ }, "cv": { "matching_model_dir": "/workspaces/obcpp/models/target_siamese_1.pt", - "segmentation_model_dir": "/workspaces/obcpp/models/fcn.pth", + "segmentation_model_dir": "/workspaces/obcpp/models/fcn-model_20-epochs_06-01-2023T21-16-02.pth", "saliency_model_dir": "/workspaces/obcpp/models/torchscript_19.pth", "not_stolen_addr": "localhost", "not_stolen_port": 5069 diff --git a/include/camera/mock.hpp b/include/camera/mock.hpp index 2eb9ca67..ef97ed27 100644 --- a/include/camera/mock.hpp +++ b/include/camera/mock.hpp @@ -6,6 +6,7 @@ #include #include #include +#include #include "camera/interface.hpp" #include "network/mavlink.hpp" @@ -50,7 +51,7 @@ class MockCamera : public CameraInterface { void startStreaming() override; private: - std::vector mock_images; + std::vector mock_images; std::atomic_bool isTakingPictures; @@ -61,6 +62,11 @@ class MockCamera : public CameraInterface { std::shared_mutex imageQueueLock; std::thread captureThread; + + // Get telemetry from JSON file adjacent to given image file. + // Ex: given path to "0003.jpg", telemetry will be looked for in + // "0003.json" + std::optional getTelemetryFromJsonFile(std::filesystem::path img_path); }; #endif // INCLUDE_CAMERA_MOCK_HPP_ diff --git a/include/cv/aggregator.hpp b/include/cv/aggregator.hpp index a642c7b8..ce71aca5 100644 --- a/include/cv/aggregator.hpp +++ b/include/cv/aggregator.hpp @@ -17,7 +17,8 @@ struct CVResults { std::vector detected_targets; // mapping from bottle -> index into detected_targets - std::unordered_map matches; + // (optional is none if we don't have a match yet) + std::unordered_map> matches; }; diff --git a/include/ticks/mission_prep.hpp b/include/ticks/mission_prep.hpp index 17bd34b4..047f85bb 100644 --- a/include/ticks/mission_prep.hpp +++ b/include/ticks/mission_prep.hpp @@ -4,6 +4,8 @@ #include #include #include +#include +#include #include "ticks/tick.hpp" #include "cv/pipeline.hpp" @@ -25,7 +27,7 @@ class MissionPrepTick : public Tick { Tick* tick() override; private: - std::vector> + std::vector> generateReferenceImages(std::array competitionObjectives); std::string getNotStolenRoute(const Bottle& target); diff --git a/src/camera/mock.cpp b/src/camera/mock.cpp index 89a1f956..a125377d 100644 --- a/src/camera/mock.cpp +++ b/src/camera/mock.cpp @@ -7,6 +7,7 @@ #include #include +#include "nlohmann/json.hpp" #include "network/mavlink.hpp" #include "utilities/locks.hpp" @@ -21,7 +22,14 @@ MockCamera::MockCamera(CameraConfig config) : CameraInterface(config) { cv::Mat img = cv::imread(dir_entry.path().string()); // if the image is read if (img.data != NULL) { - this->mock_images.push_back(img); + std::optional telemetry = + this->getTelemetryFromJsonFile(dir_entry.path()); + + ImageData img_data( + img, + 0, + telemetry); + this->mock_images.push_back(img_data); } }); } @@ -93,18 +101,41 @@ std::optional MockCamera::takePicture(const std::chrono::milliseconds std::shared_ptr mavlinkClient) { int random_idx = randomInt(0, this->mock_images.size()-1); - std::optional telemetry = queryMavlinkImageTelemetry(mavlinkClient); - - cv:Mat newImage = this->mock_images.at(random_idx); + ImageData img_data = this->mock_images.at(random_idx); uint64_t timestamp = getUnixTime_s().count(); + // if we can't find corresonding telemtry json, just query mavlink + if (!img_data.TELEMETRY.has_value()) { + img_data.TELEMETRY = queryMavlinkImageTelemetry(mavlinkClient); + } + ImageData imageData { - .DATA = newImage, + .DATA = img_data.DATA, .TIMESTAMP = timestamp, - .TELEMETRY = telemetry, + .TELEMETRY = img_data.TELEMETRY, }; return imageData; } void MockCamera::startStreaming() {} + +std::optional MockCamera::getTelemetryFromJsonFile(std::filesystem::path img_path) { + img_path.replace_extension("json"); + std::ifstream telemetry_stream(img_path); + if (!telemetry_stream.is_open()) { + // no corresponding telemetry json found + return {}; + } + nlohmann::json json = nlohmann::json::parse(telemetry_stream, nullptr, true, true); + return ImageTelemetry { + .latitude_deg = json["latitude_deg"], + .longitude_deg = json["longitude_deg"], + .altitude_agl_m = json["altitude_agl_m"], + .airspeed_m_s = json["airspeed_m_s"], + .heading_deg = json["heading_deg"], + .yaw_deg = json["yaw_deg"], + .pitch_deg = json["pitch_deg"], + .roll_deg = json["roll_deg"], + }; +} diff --git a/src/cv/aggregator.cpp b/src/cv/aggregator.cpp index 635b9844..88f4a6d2 100644 --- a/src/cv/aggregator.cpp +++ b/src/cv/aggregator.cpp @@ -7,11 +7,12 @@ CVAggregator::CVAggregator(Pipeline&& p): pipeline{p} { this->num_worker_threads = 0; this->results = std::make_shared(); - this->results->matches[BottleDropIndex::A] = -1; - this->results->matches[BottleDropIndex::B] = -1; - this->results->matches[BottleDropIndex::C] = -1; - this->results->matches[BottleDropIndex::D] = -1; - this->results->matches[BottleDropIndex::E] = -1; + // set each bottle to be initially unmatched + this->results->matches[BottleDropIndex::A] = {}; + this->results->matches[BottleDropIndex::B] = {}; + this->results->matches[BottleDropIndex::C] = {}; + this->results->matches[BottleDropIndex::D] = {}; + this->results->matches[BottleDropIndex::E] = {}; } CVAggregator::~CVAggregator() {} @@ -50,21 +51,23 @@ void CVAggregator::worker(ImageData image, int thread_num) { // newly inserted target, once we insert it after the if/else size_t detected_target_index = this->results->detected_targets.size(); - size_t curr_match_idx = this->results->matches[curr_target.likely_bottle]; - if (curr_match_idx < 0) { + std::optional curr_match_idx = + this->results->matches[curr_target.likely_bottle]; + if (!curr_match_idx.has_value()) { LOG_F(INFO, "Made first match between target %ld and bottle %d", detected_target_index, curr_target.likely_bottle); this->results->matches[curr_target.likely_bottle] = detected_target_index; } else { - auto curr_match = this->results->detected_targets[curr_match_idx]; + auto curr_match = this->results->detected_targets[curr_match_idx.value()]; if (curr_match.match_distance > curr_target.match_distance) { LOG_F(INFO, "Swapping match on bottle %d from target %ld -> %ld (distance %f -> %f)", static_cast(curr_match.likely_bottle), - this->results->matches[curr_match.likely_bottle], - detected_target_index, curr_match.match_distance, + this->results->matches[curr_match.likely_bottle].value_or(0), + detected_target_index, + curr_match.match_distance, curr_target.match_distance); this->results->matches[curr_match.likely_bottle] = detected_target_index; diff --git a/src/cv/matching.cpp b/src/cv/matching.cpp index 688bcc91..795b49ff 100644 --- a/src/cv/matching.cpp +++ b/src/cv/matching.cpp @@ -83,6 +83,9 @@ Matching::Matching(std::array * NOTE: Matching only occurs if loading model and ref. images was successful. */ MatchResult Matching::match(const CroppedTarget& croppedTarget) { + if (referenceFeatures.empty()) { + return MatchResult(BottleDropIndex::A, -std::numeric_limits::infinity()); + } std::vector input = toInput(croppedTarget.croppedImage); torch::Tensor output = this->torch_module.forward(input).toTensor(); int minIndex = 0; diff --git a/src/cv/saliency.cpp b/src/cv/saliency.cpp index 3b494fd9..3d6f9c32 100644 --- a/src/cv/saliency.cpp +++ b/src/cv/saliency.cpp @@ -35,7 +35,7 @@ std::vector Saliency::salience(cv::Mat image) { tensor = tensor.toType(c10::kFloat).div(255); // swap axis tensor = Saliency::transpose(tensor, { (2), (0), (1) }); - + // eventually add device as member of Saliency c10::Device device = torch::cuda::is_available() ? torch::kCUDA : torch::kCPU; auto tensor_cuda = tensor.to(device); @@ -60,7 +60,15 @@ std::vector Saliency::salience(cv::Mat image) { std::vector targets; targets = extractTargets(listDetections, image); - LOG_F(INFO, "salience ok"); + LOG_F(INFO, "saliency found %ld targets", targets.size()); + for (auto const& target : targets) { + LOG_F(INFO, "\ttarget at bbox: (%d, %d, %d, %d). ismannikin: %d", + target.bbox.x1, + target.bbox.y1, + target.bbox.x2, + target.bbox.y2, + target.isMannikin); + } return targets; } diff --git a/src/ticks/cv_loiter.cpp b/src/ticks/cv_loiter.cpp index aefbbb01..baa5cf41 100644 --- a/src/ticks/cv_loiter.cpp +++ b/src/ticks/cv_loiter.cpp @@ -24,6 +24,20 @@ void CVLoiterTick::setStatus(Status status) { Tick* CVLoiterTick::tick() { // Tick is called if Search Zone coverage path is finished + // // print out current state of matching for debugging + // LockPtr cv_results = this->state->getCV()->getResults(); + // for (const auto& match: cv_results.data->matches) { + // if (match.second.has_value()) { + // LOG_F(INFO, "Bottle %d is matched with target at lat: %f, lon: %f", + // match.first, + // cv_results.data->detected_targets.at(match.second.value()).coord.latitude(), + // cv_results.data->detected_targets.at(match.second.value()).coord.longitude() + // ); + // } else { + // LOG_F(INFO, "Bottle %d is not matched with a target", match.first); + // } + // } + // Check status of the CV Results if (status == Status::Validated) { return new AirdropPrepTick(this->state); diff --git a/src/ticks/fly_search.cpp b/src/ticks/fly_search.cpp index 91c51184..f8637877 100644 --- a/src/ticks/fly_search.cpp +++ b/src/ticks/fly_search.cpp @@ -57,12 +57,10 @@ Tick* FlySearchTick::tick() { } if (photo.has_value()) { - // TODO: debug why this is crashing and fix it - // Update the last photo time - // this->last_photo_time = getUnixTime_ms(); + this->last_photo_time = getUnixTime_ms(); // Run the pipeline on the photo - // this->state->getCV()->runPipeline(photo.value()); + this->state->getCV()->runPipeline(photo.value()); } } this->curr_mission_item = curr_waypoint; diff --git a/src/ticks/mission_prep.cpp b/src/ticks/mission_prep.cpp index 752da9bb..e17a35d6 100644 --- a/src/ticks/mission_prep.cpp +++ b/src/ticks/mission_prep.cpp @@ -55,25 +55,41 @@ Tick* MissionPrepTick::tick() { } -std::vector> - MissionPrepTick::generateReferenceImages(std::array competitionObjectives) { - +std::vector> MissionPrepTick::generateReferenceImages + (std::array competitionObjectives) { std::vector> ref_imgs; - int curr_bottle_idx = BottleDropIndex::A; + int curr_bottle_idx = BottleDropIndex::Undefined; for (const auto& bottle : competitionObjectives) { - httplib::Client client(this->state->config.cv.not_stolen_addr, this->state->config.cv.not_stolen_port); + curr_bottle_idx++; + + // don't generate reference images for mannikin since matching model doesn't + // match mannikins (handled by saliency) + if (bottle.ismannikin()) { + continue; + } + + httplib::Client client(this->state->config.cv.not_stolen_addr, + this->state->config.cv.not_stolen_port); auto res = client.Get(this->getNotStolenRoute(bottle)); + // connection failed + if (!res) { + LOG_F(ERROR, "Failed to send request to not-stolen at %s:%u. Reason: %s", + this->state->config.cv.not_stolen_addr.c_str(), + this->state->config.cv.not_stolen_port, + httplib::to_string(res.error()).c_str()); + return {}; + } + if (res->status != 200) { LOG_F(ERROR, "Got invalid response from not-stolen: %s", res->body.c_str()); continue; } - std::vector vectordata(res->body.begin(),res->body.end()); + std::vector vectordata(res->body.begin(), res->body.end()); cv::Mat data_mat(vectordata, true); - cv::Mat ref_img(cv::imdecode(data_mat,1)); //put 0 if you want greyscale + cv::Mat ref_img(cv::imdecode(data_mat, 1)); // put 0 if you want greyscale ref_imgs.push_back({ref_img, (BottleDropIndex)curr_bottle_idx}); - curr_bottle_idx++; } return ref_imgs; } @@ -85,7 +101,7 @@ std::string MissionPrepTick::getNotStolenRoute(const Bottle& target) { std::string shape_type = ODLCShapeToString(target.shape()); std::string shape_color = ODLCColorToString(target.shapecolor()); - return std::string("/generate?shape_type=") + shape_type + + return std::string("/generate?shape_type=") + shape_type + std::string("&shape_color=") + shape_color + std::string("&char_type=") + char_type + std::string("&char_color=") + char_color; diff --git a/src/utilities/datatypes.cpp b/src/utilities/datatypes.cpp index d86d70f4..b8ce733b 100644 --- a/src/utilities/datatypes.cpp +++ b/src/utilities/datatypes.cpp @@ -126,7 +126,7 @@ std::string ODLCColorToString(const ODLCColor& color) { case ODLCColor::Brown: return "BROWN"; case ODLCColor::Orange: return "ORANGE"; // maybe return optional nullopt here instead of defaulting to WHITE - // in case of an unknown color + // in case of an unknown color default: return "WHITE"; } -} \ No newline at end of file +} diff --git a/tests/integration/cv_pipeline.cpp b/tests/integration/cv_pipeline.cpp index e8af8f8c..701f5c95 100644 --- a/tests/integration/cv_pipeline.cpp +++ b/tests/integration/cv_pipeline.cpp @@ -5,28 +5,58 @@ #include "cv/pipeline.hpp" -// Download these test images from one of the zips here https://drive.google.com/drive/u/1/folders/1opXBWx6bBF7J3-JSFtrhfFIkYis9qhGR -// Or, any cropped not-stolen images will work -// this image should be located at a relative path to the CMake build dir -const std::string imagePath = "mock_image.jpg"; +// NOTE: all paths to images should be located at a relative path to the CMake build dir. +// You can download all images with `ninja pull_test_images` + +// Download by running `ninja pull_saliency_test_images` or from this drive folder +// https://drive.google.com/drive/folders/1JvtQUroZJHo51E37_IA2D1mfdJj2smyR?usp=drive_link +const std::string imagePath = "../tests/integration/images/saliency/1718243323.jpg"; + +// Download these test images from here https://drive.google.com/drive/folders/1vmP3HUS1SyqhdtJrP4QuFpGbyoyfaYSe?usp=drive_link +// Or, any cropped not-stolen images will work -const std::string refImagePath0 = "../bin/test/test/000000910.jpg"; -const std::string refImagePath1 = "../bin/test/test/000000920.jpg"; -const std::string refImagePath2 = "../bin/test/test/000000003.jpg"; -const std::string refImagePath3 = "../bin/test/test/000000004.jpg"; -const std::string refImagePath4 = "../bin/test/test/000000005.jpg"; +#define NUM_MATCHING_IMAGES 20 +// Directories to matching images. Note that each element of this array is a std::pair. +// The first member is the path to the image and the second member is the bottle each matching +// image corresponds to. See the body of main() for what shape/char/color each bottle is assigned to. +const std::array, NUM_MATCHING_IMAGES> matchingImgPaths = { + std::make_pair("../tests/integration/images/matching/green_rect_purple_B_1.jpg", BottleDropIndex::B), + std::make_pair("../tests/integration/images/matching/green_rect_purple_B_2.jpg", BottleDropIndex::B), + std::make_pair("../tests/integration/images/matching/green_rect_purple_B_3.jpg", BottleDropIndex::B), + std::make_pair("../tests/integration/images/matching/green_rect_purple_B_4.jpg", BottleDropIndex::B), + std::make_pair("../tests/integration/images/matching/green_rect_purple_B_5.jpg", BottleDropIndex::B), + + std::make_pair("../tests/integration/images/matching/red_triangle_purple_E_1.jpg", BottleDropIndex::C), + std::make_pair("../tests/integration/images/matching/red_triangle_purple_E_2.jpg", BottleDropIndex::C), + std::make_pair("../tests/integration/images/matching/red_triangle_purple_E_3.jpg", BottleDropIndex::C), + std::make_pair("../tests/integration/images/matching/red_triangle_purple_E_4.jpg", BottleDropIndex::C), + std::make_pair("../tests/integration/images/matching/red_triangle_purple_E_5.jpg", BottleDropIndex::C), + + std::make_pair("../tests/integration/images/matching/blue_pent_green_Q_1.jpg", BottleDropIndex::D), + std::make_pair("../tests/integration/images/matching/blue_pent_green_Q_2.jpg", BottleDropIndex::D), + std::make_pair("../tests/integration/images/matching/blue_pent_green_Q_3.jpg", BottleDropIndex::D), + std::make_pair("../tests/integration/images/matching/blue_pent_green_Q_4.jpg", BottleDropIndex::D), + std::make_pair("../tests/integration/images/matching/blue_pent_green_Q_5.jpg", BottleDropIndex::D), + + std::make_pair("../tests/integration/images/matching/blue_pent_orange_3_1.jpg", BottleDropIndex::E), + std::make_pair("../tests/integration/images/matching/blue_pent_orange_3_2.jpg", BottleDropIndex::E), + std::make_pair("../tests/integration/images/matching/blue_pent_orange_3_3.jpg", BottleDropIndex::E), + std::make_pair("../tests/integration/images/matching/blue_pent_orange_3_4.jpg", BottleDropIndex::E), + std::make_pair("../tests/integration/images/matching/blue_pent_orange_3_5.jpg", BottleDropIndex::E), +}; // matching model can be downloaded from here: https://drive.google.com/drive/folders/1ciDfycNyJiLvRhJhwQZoeKH7vgV6dGHJ?usp=drive_link const std::string matchingModelPath = "../models/target_siamese_1.pt"; // segmentation model can be downloaded from here: https://drive.google.com/file/d/1U2EbfJFzcjVnjTuD6ud-bIf8YOiEassf/view?usp=drive_link -const std::string segmentationModelPath = "../models/fcn.pth"; +const std::string segmentationModelPath = "../models/fcn-model_20-epochs_06-01-2023T21-16-02.pth"; +const std::string saliencyModelPath = "../models/torchscript_19.pth"; // mock telemetry data -const double latitude = 38.31568; -const double longitude = 76.55006; -const double altitude = 75; -const double airspeed = 20; +const double latitude = 32.990795399999996; +const double longitude = -117.1282463; +const double altitude = 30.108001708984375; +const double airspeed = 7.378872394561768; const double yaw = 100; const double pitch = 5; const double roll = 3; @@ -35,60 +65,60 @@ const double roll = 3; // with an arbitrary image as input int main() { cv::Mat image = cv::imread(imagePath); + if (!image.data) { + std::cout << "failed to open testing image from " << imagePath << std::endl; + return 1; + } ImageTelemetry mockTelemetry(latitude, longitude, altitude, airspeed, yaw, pitch, roll); - ImageData imageData("mock_image", imagePath, image, mockTelemetry); + ImageData imageData(image, 0, mockTelemetry); std::array bottlesToDrop; + // Bottle A Bottle bottle1; - bottle1.set_shapecolor(ODLCColor::Red); - bottle1.set_shape(ODLCShape::Circle); - bottle1.set_alphanumericcolor(ODLCColor::Orange); - bottle1.set_alphanumeric("J"); + bottle1.set_ismannikin(true); bottlesToDrop[0] = bottle1; + // Bottle B Bottle bottle2; - bottle2.set_shapecolor(ODLCColor::Blue); - bottle2.set_shape(ODLCShape::Circle); - bottle2.set_alphanumericcolor(ODLCColor::Orange); - bottle2.set_alphanumeric("G"); + bottle2.set_shapecolor(ODLCColor::Green); + bottle2.set_shape(ODLCShape::Rectangle); + bottle2.set_alphanumericcolor(ODLCColor::Purple); + bottle2.set_alphanumeric("B"); bottlesToDrop[1] = bottle2; + // Bottle C Bottle bottle3; bottle3.set_shapecolor(ODLCColor::Red); - bottle3.set_shape(ODLCShape::Circle); - bottle3.set_alphanumericcolor(ODLCColor::Blue); - bottle3.set_alphanumeric("X"); + bottle3.set_shape(ODLCShape::Triangle); + bottle3.set_alphanumericcolor(ODLCColor::Purple); + bottle3.set_alphanumeric("E"); bottlesToDrop[2] = bottle3; + // Bottle D Bottle bottle4; - bottle4.set_shapecolor(ODLCColor::Red); - bottle4.set_shape(ODLCShape::Circle); - bottle4.set_alphanumericcolor(ODLCColor::Blue); - bottle4.set_alphanumeric("F"); + bottle4.set_shapecolor(ODLCColor::Blue); + bottle4.set_shape(ODLCShape::Pentagon); + bottle4.set_alphanumericcolor(ODLCColor::Green); + bottle4.set_alphanumeric("Q"); bottlesToDrop[3] = bottle4; + // Bottle E Bottle bottle5; - bottle5.set_shapecolor(ODLCColor::Green); - bottle5.set_shape(ODLCShape::Circle); - bottle5.set_alphanumericcolor(ODLCColor::Black); - bottle5.set_alphanumeric("F"); + bottle5.set_shapecolor(ODLCColor::Blue); + bottle5.set_shape(ODLCShape::Pentagon); + bottle5.set_alphanumericcolor(ODLCColor::Orange); + bottle5.set_alphanumeric("3"); bottlesToDrop[4] = bottle5; std::vector> referenceImages; - cv::Mat ref0 = cv::imread(refImagePath0); - referenceImages.push_back(std::make_pair(ref0, BottleDropIndex(5))); - cv::Mat ref1 = cv::imread(refImagePath1); - referenceImages.push_back(std::make_pair(ref1, BottleDropIndex(4))); - cv::Mat ref2 = cv::imread(refImagePath2); - referenceImages.push_back(std::make_pair(ref2, BottleDropIndex(3))); - cv::Mat ref3 = cv::imread(refImagePath3); - referenceImages.push_back(std::make_pair(ref3, BottleDropIndex(2))); - cv::Mat ref4 = cv::imread(refImagePath4); - referenceImages.push_back(std::make_pair(ref4, BottleDropIndex(1))); - - Pipeline pipeline(PipelineParams(bottlesToDrop, referenceImages, matchingModelPath, segmentationModelPath)); + for (const auto& [matchingImgPath, assignedBottle]: matchingImgPaths) { + cv::Mat refImg = cv::imread(matchingImgPath); + referenceImages.push_back(std::make_pair(refImg, assignedBottle)); + } + + Pipeline pipeline(PipelineParams(bottlesToDrop, referenceImages, matchingModelPath, segmentationModelPath, saliencyModelPath)); PipelineResults output = pipeline.run(imageData); diff --git a/tests/integration/images/saliency/.gitkeep b/tests/integration/images/saliency/.gitkeep deleted file mode 100644 index e69de29b..00000000