Skip to content

Commit

Permalink
lint
Browse files Browse the repository at this point in the history
  • Loading branch information
atar13 committed Jun 23, 2024
1 parent 18049fa commit 303ed72
Show file tree
Hide file tree
Showing 9 changed files with 29 additions and 26 deletions.
2 changes: 1 addition & 1 deletion include/camera/mock.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,7 @@ class MockCamera : public CameraInterface {
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
// Ex: given path to "0003.jpg", telemetry will be looked for in
// "0003.json"
std::optional<ImageTelemetry> getTelemetryFromJsonFile(std::filesystem::path img_path);
};
Expand Down
2 changes: 1 addition & 1 deletion include/cv/aggregator.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@

struct CVResults {
std::vector<DetectedTarget> detected_targets;
// mapping from bottle -> index into detected_targets
// mapping from bottle -> index into detected_targets
// (optional is none if we don't have a match yet)
std::unordered_map<BottleDropIndex, std::optional<size_t>> matches;
};
Expand Down
4 changes: 3 additions & 1 deletion include/ticks/mission_prep.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,8 @@
#include <memory>
#include <chrono>
#include <string>
#include <utility>
#include <vector>

#include "ticks/tick.hpp"
#include "cv/pipeline.hpp"
Expand All @@ -25,7 +27,7 @@ class MissionPrepTick : public Tick {

Tick* tick() override;
private:
std::vector<std::pair<cv::Mat, BottleDropIndex>>
std::vector<std::pair<cv::Mat, BottleDropIndex>>
generateReferenceImages(std::array<Bottle, NUM_AIRDROP_BOTTLES> competitionObjectives);

std::string getNotStolenRoute(const Bottle& target);
Expand Down
10 changes: 5 additions & 5 deletions src/camera/mock.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,13 +22,13 @@ MockCamera::MockCamera(CameraConfig config) : CameraInterface(config) {
cv::Mat img = cv::imread(dir_entry.path().string());
// if the image is read
if (img.data != NULL) {
std::optional<ImageTelemetry> telemetry = this->getTelemetryFromJsonFile(dir_entry.path());
std::optional<ImageTelemetry> telemetry =
this->getTelemetryFromJsonFile(dir_entry.path());

ImageData img_data(
img,
0,
telemetry
);
telemetry);
this->mock_images.push_back(img_data);
}
});
Expand Down Expand Up @@ -126,7 +126,7 @@ std::optional<ImageTelemetry> MockCamera::getTelemetryFromJsonFile(std::filesyst
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"],
Expand All @@ -138,4 +138,4 @@ std::optional<ImageTelemetry> MockCamera::getTelemetryFromJsonFile(std::filesyst
.pitch_deg = json["pitch_deg"],
.roll_deg = json["roll_deg"],
};
}
}
3 changes: 2 additions & 1 deletion src/cv/aggregator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,8 @@ 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();

std::optional<size_t> curr_match_idx = this->results->matches[curr_target.likely_bottle];
std::optional<size_t> 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);
Expand Down
12 changes: 6 additions & 6 deletions src/cv/saliency.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ std::vector<CroppedTarget> 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);
Expand All @@ -61,12 +61,12 @@ std::vector<CroppedTarget> Saliency::salience(cv::Mat image) {
targets = extractTargets(listDetections, image);

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,
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.bbox.x2,
target.bbox.y2,
target.isMannikin);
}
return targets;
Expand Down
4 changes: 2 additions & 2 deletions src/ticks/cv_loiter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,12 +23,12 @@ 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<CVResults> 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",
// 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()
Expand Down
14 changes: 7 additions & 7 deletions src/ticks/mission_prep.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,9 +55,8 @@ Tick* MissionPrepTick::tick() {
}


std::vector<std::pair<cv::Mat, BottleDropIndex>>
MissionPrepTick::generateReferenceImages(std::array<Bottle, NUM_AIRDROP_BOTTLES> competitionObjectives) {

std::vector<std::pair<cv::Mat, BottleDropIndex>> MissionPrepTick::generateReferenceImages
(std::array<Bottle, NUM_AIRDROP_BOTTLES> competitionObjectives) {
std::vector<std::pair<cv::Mat, BottleDropIndex>> ref_imgs;

int curr_bottle_idx = BottleDropIndex::Undefined;
Expand All @@ -70,7 +69,8 @@ std::vector<std::pair<cv::Mat, BottleDropIndex>>
continue;
}

httplib::Client client(this->state->config.cv.not_stolen_addr, this->state->config.cv.not_stolen_port);
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) {
Expand All @@ -85,9 +85,9 @@ std::vector<std::pair<cv::Mat, BottleDropIndex>>
LOG_F(ERROR, "Got invalid response from not-stolen: %s", res->body.c_str());
continue;
}
std::vector<uint8_t> vectordata(res->body.begin(),res->body.end());
std::vector<uint8_t> 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});
}
Expand All @@ -101,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;
Expand Down
4 changes: 2 additions & 2 deletions src/utilities/datatypes.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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";
}
}
}

0 comments on commit 303ed72

Please sign in to comment.