Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Long Range Object Detector #16

Open
wants to merge 26 commits into
base: main
Choose a base branch
from
Open

Conversation

jbrhm
Copy link
Contributor

@jbrhm jbrhm commented Sep 30, 2024

Summary

Closes #14

What features did you add, bugs did you fix, etc?
I added the long range object detector

Did you add documentation to the wiki?

No, its already on the wiki

How was this code tested?

Tested on usb camera while also running the regular object detector

Did you test this in sim?

No

Did you test this on the rover?

No

Did you add unit tests?

No

@jbrhm jbrhm requested a review from alisonryckman September 30, 2024 21:20
@jbrhm jbrhm self-assigned this Sep 30, 2024
jbrhm and others added 4 commits September 30, 2024 17:22
* ZED Naming conflicts

* OD in the sim and on ZED

* style

* style
std::vector<int64_t> outputTensorSize;

// Additional space for params that one algorithm might need and not others
std::vector<float> buffer;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

rethink the buffer, unspecified size is not ideal

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Yes, this was a bad feature making non static calls is def the move

}

int rows = output.cols;
int dimensions = output.rows;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

can you name this more verbosely

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Changed

@@ -50,18 +70,43 @@ namespace mrover {

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

image should be const ref

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Ok, I changed publishDetectedObjects to const ref, drawDetectionBoxes to just ref and rgbImage in preprocessYOLOv8Input to const ref, lmk if i missed any

public:
explicit ImageObjectDetector();

auto getTagBearing(cv::InputArray image, cv::Rect const& box) const -> float;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

image const ref

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

adjusted

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

don't include in this PR

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

removed

}

// Be verbose about the input tensor size
auto outputTensorSize = getInputTensorSize();
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

auto outputTensorSize = getOutputTensorSize();

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

done

std::ofstream outputFileStream{enginePath, std::ios::binary};
outputFileStream.write(static_cast<char const*>(trtModelStream->data()), trtModelStream->size());
std::ofstream outputFileStream{mEngineModelPath, std::ios::binary};
outputFileStream.write(static_cast<char const*>(trtModelStream->data()), static_cast<int32_t>(trtModelStream->size()));
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

why int32 cast?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

narrowing conversion, but I made it more clear

@@ -153,7 +182,8 @@ auto Inference::prepTensors() -> void {

assert(mContext);
// Create an appropriately sized output tensor
auto const [nbDims, d] = mEngine->getTensorShape(OUTPUT_BINDING_NAME);
// TODO: Fix this
auto const [nbDims, d] = mEngine->getTensorShape(mOutputTensorName.c_str());
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

this TODO still relevant?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

No it is not

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

removed

@@ -170,3 +200,28 @@ auto Inference::getBindingInputIndex(IExecutionContext const* context) -> int {
// Returns the id for the input tensor
return context->getEngine().getTensorIOMode(context->getEngine().getIOTensorName(0)) != TensorIOMode::kINPUT; // 0 (false) if bindingIsInput(0), 1 (true) otherwise
}


auto Inference::getInputTensorSize() -> std::vector<int64_t>{
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Do you really need two separate functions for input and output?

Comment on lines +82 to +96
// Fill in the output Detections Vector
for (int i: nmsResult) {
Detection result;

//Fill in the id and confidence for the class
result.classId = classIds[i];
result.confidence = confidences[i];

//Fill in the class name and box information
result.className = model.classes[result.classId];
result.box = boxes[i];

//Push back the detection into the for storagevector
detections.push_back(result);
}
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Can this be made more concise?

Comment on lines +207 to +212
for (auto const& [classId, className, confidence, box]: detections) {
mrover::msg::ImageTarget target;
target.name = className;
target.bearing = getTagBearing(blobSizedImage, box);
targets.targets.push_back(target);
}
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

surely this could be emplace_back

@@ -112,7 +112,7 @@ def paintEvent(self, event):
self.resize(self.renderer.defaultSize())
self.renderer.render(painter)

def update(self):
def update(self): # type: ignore[override]
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I feel this is not relevant to the PR

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

Successfully merging this pull request may close these issues.

Udate Object Detector with Long Range Functionality
3 participants