robokudo.utils.cv_helper¶
OpenCV helper utilities for Robokudo.
This module provides helper functions for working with OpenCV images and operations. It supports:
Image cropping and ROI handling
ROS-OpenCV image conversion
Color space conversions
Bounding box operations
Image scaling and resizing
Drawing utilities
The module integrates with: * OpenCV for image processing * ROS for image message handling * NumPy for numerical operations * CAS for data management
Attributes¶
Functions¶
|
Crop region from image using coordinates and dimensions. |
|
Crop region from image using ROI object. |
|
Convert ROS image message to OpenCV image. |
|
Convert OpenCV image to ROS image message. |
Scale color image to match depth image resolution. |
|
|
Scale coordinates based on color-to-depth ratio. |
|
Convert RGB color to HSV color space. |
|
Convert BGR color to HSV color space. |
|
Draw filled rectangle centered at given point. |
|
Clamp bounding rectangle to image boundaries. |
|
Check if bounding rectangle is valid for image dimensions. |
|
Adjusts the ROI by a given offset while respecting image boundaries, keeping the same center point. |
|
Adjusts the ImageROI's ROI by a given offset while respecting image boundaries, |
|
Adjusts the mask by a given offset. When expanding, the new areas are filled |
Module Contents¶
- robokudo.utils.cv_helper.LOGGER = None¶
- robokudo.utils.cv_helper.crop_image(image: numpy.typing.NDArray, xy: tuple, wh: tuple) numpy.typing.NDArray¶
-
Crop region from image using coordinates and dimensions.
Based on https://stackoverflow.com/a/67799880
- Parameters:
-
image (npt.NDArray) – Input image
xy (tuple) – Top-left corner coordinates (x,y)
wh (tuple) – Width and height of crop region (w,h)
- Returns:
-
Cropped image region
- Return type:
-
npt.NDArray
- robokudo.utils.cv_helper.crop_image_roi(image: numpy.typing.NDArray, roi: robokudo.types.cv.ImageROI) numpy.typing.NDArray¶
-
Crop region from image using ROI object.
- Parameters:
-
image (npt.NDArray) – Input image
roi (robokudo.types.cv.ImageROI) – Region of interest
- Returns:
-
Cropped image region
- Return type:
-
npt.NDArray
- robokudo.utils.cv_helper.convert_ros_to_cv_image(ros_image) numpy.typing.NDArray¶
-
Convert ROS image message to OpenCV image.
- Parameters:
-
ros_image (sensor_msgs.Image) – ROS image message
- Returns:
-
OpenCV image array
- Return type:
-
npt.NDArray
- Raises:
-
CvBridgeError – If conversion fails
- robokudo.utils.cv_helper.convert_cv_to_ros_image(cv_image)¶
-
Convert OpenCV image to ROS image message.
- Parameters:
-
cv_image (npt.NDArray) – OpenCV image array
- Returns:
-
ROS image message
- Return type:
-
sensor_msgs.Image
- Raises:
-
CvBridgeError – If conversion fails
- robokudo.utils.cv_helper.get_scaled_color_image_for_depth_image(cas: robokudo.cas.CAS, color_image: numpy.typing.NDArray) numpy.typing.NDArray¶
-
Scale color image to match depth image resolution.
If the color2depth ratio is not 1,1, we will usually scale the color image to the same size the depth image has. This method will get check if a conversion is required and will return the correct size. This is usually called before o3d.geometry.RGBDImage.create_from_color_and_depth is called, so that depth and color image match.
- Parameters:
-
cas (robokudo.cas.CAS) – The robokudo.cas.CAS where the COLOR2DEPTH_RATIO is stored.
color_image (npt.NDArray) – The color image to be adjusted
- Returns:
-
A resized copy of the color image if a resize necessary. Otherwise, the unchanged color_image
is returned. :rtype: npt.NDArray :raises RuntimeError: If color-to-depth ratio not set in CAS
- robokudo.utils.cv_helper.get_scale_coordinates(color2depth_ratio: tuple, coordinates: tuple) tuple¶
-
Scale coordinates based on color-to-depth ratio.
- Parameters:
-
color2depth_ratio (tuple) – Scale factors (x_scale, y_scale)
coordinates (tuple) – Input coordinates (x, y)
- Returns:
-
Scaled coordinates
- Return type:
-
tuple
- Raises:
-
RuntimeError – If color-to-depth ratio not provided
- robokudo.utils.cv_helper.get_hsv_for_rgb_color(rgb: tuple) numpy.typing.NDArray¶
-
Convert RGB color to HSV color space.
- Parameters:
-
rgb (tuple) – RGB color values (r,g,b)
- Returns:
-
HSV color values
- Return type:
-
npt.NDArray
- robokudo.utils.cv_helper.get_hsv_for_bgr_color(bgr: tuple) numpy.typing.NDArray¶
-
Convert BGR color to HSV color space.
- Parameters:
-
bgr (tuple) – BGR color values (b,g,r)
- Returns:
-
HSV color values
- Return type:
-
npt.NDArray
- robokudo.utils.cv_helper.draw_rectangle_around_center(binary_image: numpy.typing.NDArray, x: int, y: int, width: int, height: int, value: int = 255) numpy.typing.NDArray¶
-
Draw filled rectangle centered at given point.
- Parameters:
-
binary_image (npt.NDArray) – Binary image to draw on
x (int) – Center x coordinate
y (int) – Center y coordinate
width (int) – Rectangle width
height (int) – Rectangle height
value (int) – Fill value for rectangle
- Returns:
-
Image with drawn rectangle
- Return type:
-
npt.NDArray
- robokudo.utils.cv_helper.clamp_bounding_rect(bounding_rect: cv2.boundingRect, image_width: int, image_height: int) cv2.boundingRect¶
-
Clamp bounding rectangle to image boundaries.
- Parameters:
-
bounding_rect (cv2.boundingRect) – Input bounding rectangle (x,y,w,h)
image_width (int) – Image width
image_height (int) – Image height
- Returns:
-
Clamped bounding rectangle
- Return type:
-
cv2.boundingRect
- robokudo.utils.cv_helper.sanity_checks_bounding_rects(bounding_rect: cv2.boundingRect, image_width: int, image_height: int)¶
-
Check if bounding rectangle is valid for image dimensions.
Check basic rules of a boundingRect to reject bad ones. Might happen if projections are done on objects that are out-of-view etc.
- Parameters:
-
bounding_rect (cv2.boundingRect) – Bounding rectangle to check (x,y,w,h)
image_width (int) – Image width
image_height (int) – Image height
- Returns:
-
True if rules have been passed, False otherwise
- Return type:
-
bool
- robokudo.utils.cv_helper.adjust_roi(image: numpy.typing.NDArray, roi: tuple, offset: int) tuple¶
-
Adjusts the ROI by a given offset while respecting image boundaries, keeping the same center point.
- Parameters:
-
image (npt.NDArray) – The image (OpenCV format).
roi (tuple) – A tuple (x, y, width, height) representing the bounding box.
offset (int) – The amount by which to grow or shrink the ROI (can be negative).
- Returns:
-
A tuple (new_x, new_y, new_width, new_height) representing the adjusted ROI.
- Return type:
-
tuple
- robokudo.utils.cv_helper.adjust_image_roi(image: numpy.typing.NDArray, image_roi: robokudo.types.cv.ImageROI, offset: int) None¶
-
Adjusts the ImageROI’s ROI by a given offset while respecting image boundaries, keeping the same center point. This method uses the adjust_roi function.
- Parameters:
-
image (npt.NDArray) – The image this ROI is relative to. Necessary to respect the boundaries properly.
image_roi (robokudo.types.cv.ImageROI) – An object of type ImageROI.
offset (int) – The amount by which to grow or shrink the ROI (can be negative).
- Returns:
-
None. The ImageROI’s ROI is adjusted in place.
- robokudo.utils.cv_helper.adjust_mask(mask: numpy.typing.NDArray, offset: int, fill_value: int = 0) numpy.typing.NDArray¶
-
Adjusts the mask by a given offset. When expanding, the new areas are filled with the specified fill value.
- Parameters:
-
mask (npt.NDArray) – The mask corresponding to the ROI (same dimensions as the ROI).
offset (int) – The amount by which to grow or shrink the mask (can be negative).
fill_value (int) – The value to fill new areas when expanding the mask.
- Returns:
-
The adjusted mask.
- Return type:
-
npt.NDArray