Skip to content

Commit

Permalink
Added parameters to filter bounding boxes based on size. (#49)
Browse files Browse the repository at this point in the history
* Added parameters to filter bounding boxes based on size.

* Added callback for validating parameters
  • Loading branch information
ndelima-ekumen authored Sep 20, 2024
1 parent d920ad0 commit e2505aa
Show file tree
Hide file tree
Showing 2 changed files with 81 additions and 1 deletion.
4 changes: 4 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -190,6 +190,10 @@ docker compose -f docker/docker-compose.yml --profile simulated_pipeline up
docker compose -f docker/docker-compose.yml --profile simulated_pipeline down
```

### Minimum bounding box tuning

There are two parameters (`bbox_min_x` and `bbox_min_y`, both measured in pixels) available in the detection node, that can be used to filter the inferences based on the size of the bounding boxes generated. They can be modified via rqt_gui (Plugins -> Configuration -> Dynamic Reconfigure).

## Test

### Detection stack
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,8 @@
QoSProfile,
ReliabilityPolicy,
)
from rclpy.parameter import Parameter
from rcl_interfaces.msg import SetParametersResult
from sensor_msgs.msg import CompressedImage, Image
from std_msgs.msg import Header
from vision_msgs.msg import (
Expand Down Expand Up @@ -77,6 +79,12 @@ class FruitDetectionNode(Node):
RECT_COLOR = (0, 0, 255)
SCORE_THRESHOLD = 0.7
LOGGING_THROTTLE = 1
DEFAULT_BBOX_SIZE_X = 50
DEFAULT_BBOX_SIZE_Y = 50
MINIMUM_BBOX_SIZE_X = 0
MINIMUM_BBOX_SIZE_Y = 0
MAXIMUM_BBOX_SIZE_X = 640
MAXIMUM_BBOX_SIZE_Y = 480

def __init__(self) -> None:
"""Initialize the node."""
Expand All @@ -86,6 +94,16 @@ def __init__(self) -> None:
self.declare_parameter(
"olive_camera_topic", "/olive/camera/id02/image/compressed"
)
self.declare_parameter(
"bbox_min_x",
FruitDetectionNode.DEFAULT_BBOX_SIZE_X,
)
self.declare_parameter(
"bbox_min_y",
FruitDetectionNode.DEFAULT_BBOX_SIZE_Y,
)

self.add_on_set_parameters_callback(self.validate_parameters)

self.__model_path = (
self.get_parameter("model_path").get_parameter_value().string_value
Expand Down Expand Up @@ -133,6 +151,34 @@ def __init__(self) -> None:
self.get_logger().info("ingestion;inference;plot;detection;publish;")
self.ingest_transform = get_transform()

def validate_parameters(self, params):
"""
Validate parameter changes.
:param params: list of parameters.
:return: SetParametersResult.
"""
parameters_are_valid = True
for param in params:
if param.name == "bbox_min_x":
if param.type_ != Parameter.Type.INTEGER or not (
FruitDetectionNode.MINIMUM_BBOX_SIZE_X
<= param.value
<= FruitDetectionNode.MAXIMUM_BBOX_SIZE_X
):
parameters_are_valid = False
break
elif param.name == "bbox_min_y":
if param.type_ != Parameter.Type.INTEGER or not (
FruitDetectionNode.MINIMUM_BBOX_SIZE_Y
<= param.value
<= FruitDetectionNode.MAXIMUM_BBOX_SIZE_Y
):
parameters_are_valid = False
break
return SetParametersResult(successful=parameters_are_valid)

def load_model(self):
"""Load the torch model."""
self.model = fasterrcnn_resnet50_fpn(weights=None)
Expand All @@ -159,6 +205,19 @@ def cv2_to_torch_frame(self, img):
"""Prepare cv2 image for inference."""
return self.image_to_tensor(cv2.cvtColor(img, cv2.COLOR_BGR2RGB))

def bbox_has_minimum_size(self, box, min_x, min_y):
"""
Check if a box is bigger than a minimum size.
:param box: bounding box from inference.
:param min_x: minimum horizontal length of the bounding box.
:param min_y: minimum vertical length of the bounding box.
:return: True if the box has the minimum size.
"""
x1, y1, x2, y2 = int(box[0]), int(box[1]), int(box[2]), int(box[3])
return (min_x <= (x2 - x1)) and (min_y <= (y2 - y1))

def score_frame(self, frame):
"""
Score each frame of the video and return results.
Expand All @@ -179,7 +238,24 @@ def score_frame(self, frame):
for i, (box, score, label) in enumerate(
zip(output["boxes"], output["scores"], output["labels"])
):
if score >= FruitDetectionNode.SCORE_THRESHOLD:
bbox_min_x = (
self.get_parameter("bbox_min_x")
.get_parameter_value()
.integer_value # Minimum bbox x size
)
bbox_min_y = (
self.get_parameter("bbox_min_y")
.get_parameter_value()
.integer_value # Minimum bbox y size
)
if (
score >= FruitDetectionNode.SCORE_THRESHOLD
and self.bbox_has_minimum_size(
box,
bbox_min_x,
bbox_min_y,
)
):
results.append(
{
"box": box,
Expand Down

0 comments on commit e2505aa

Please sign in to comment.