robokudo.utils.cv_helper ======================== .. py:module:: robokudo.utils.cv_helper .. autoapi-nested-parse:: 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 ---------- .. autoapisummary:: robokudo.utils.cv_helper.LOGGER Functions --------- .. autoapisummary:: robokudo.utils.cv_helper.crop_image robokudo.utils.cv_helper.crop_image_roi robokudo.utils.cv_helper.convert_ros_to_cv_image robokudo.utils.cv_helper.convert_cv_to_ros_image robokudo.utils.cv_helper.get_scaled_color_image_for_depth_image robokudo.utils.cv_helper.get_scale_coordinates robokudo.utils.cv_helper.get_hsv_for_rgb_color robokudo.utils.cv_helper.get_hsv_for_bgr_color robokudo.utils.cv_helper.draw_rectangle_around_center robokudo.utils.cv_helper.clamp_bounding_rect robokudo.utils.cv_helper.rect_outside_image robokudo.utils.cv_helper.sanity_checks_bounding_rects robokudo.utils.cv_helper.adjust_roi robokudo.utils.cv_helper.adjust_image_roi robokudo.utils.cv_helper.adjust_mask Module Contents --------------- .. py:data:: LOGGER :value: None .. py:function:: 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 :param image: Input image :type image: npt.NDArray :param xy: Top-left corner coordinates (x,y) :type xy: tuple :param wh: Width and height of crop region (w,h) :type wh: tuple :return: Cropped image region :rtype: npt.NDArray .. py:function:: crop_image_roi(image: numpy.typing.NDArray, roi: robokudo.types.cv.ImageROI) -> numpy.typing.NDArray Crop region from image using ROI object. :param image: Input image :type image: npt.NDArray :param roi: Region of interest :type roi: robokudo.types.cv.ImageROI :return: Cropped image region :rtype: npt.NDArray .. py:function:: convert_ros_to_cv_image(ros_image) -> numpy.typing.NDArray Convert ROS image message to OpenCV image. :param ros_image: ROS image message :type ros_image: sensor_msgs.Image :return: OpenCV image array :rtype: npt.NDArray :raises CvBridgeError: If conversion fails .. py:function:: convert_cv_to_ros_image(cv_image) Convert OpenCV image to ROS image message. :param cv_image: OpenCV image array :type cv_image: npt.NDArray :return: ROS image message :rtype: sensor_msgs.Image :raises CvBridgeError: If conversion fails .. py:function:: 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. :param cas: The robokudo.cas.CAS where the COLOR2DEPTH_RATIO is stored. :type cas: robokudo.cas.CAS :param color_image: The color image to be adjusted :type color_image: npt.NDArray :return: 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 .. py:function:: get_scale_coordinates(color2depth_ratio: tuple, coordinates: tuple) -> tuple Scale coordinates based on color-to-depth ratio. :param color2depth_ratio: Scale factors (x_scale, y_scale) :type color2depth_ratio: tuple :param coordinates: Input coordinates (x, y) :type coordinates: tuple :return: Scaled coordinates :rtype: tuple :raises RuntimeError: If color-to-depth ratio not provided .. py:function:: get_hsv_for_rgb_color(rgb: tuple) -> numpy.typing.NDArray Convert RGB color to HSV color space. :param rgb: RGB color values (r,g,b) :type rgb: tuple :return: HSV color values :rtype: npt.NDArray .. py:function:: get_hsv_for_bgr_color(bgr: tuple) -> numpy.typing.NDArray Convert BGR color to HSV color space. :param bgr: BGR color values (b,g,r) :type bgr: tuple :return: HSV color values :rtype: npt.NDArray .. py:function:: 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. :param binary_image: Binary image to draw on :type binary_image: npt.NDArray :param x: Center x coordinate :type x: int :param y: Center y coordinate :type y: int :param width: Rectangle width :type width: int :param height: Rectangle height :type height: int :param value: Fill value for rectangle :type value: int :return: Image with drawn rectangle :rtype: npt.NDArray .. py:function:: clamp_bounding_rect(bounding_rect: cv2.typing.Rect, image_width: int, image_height: int) -> cv2.typing.Rect Clamp bounding rectangle to image boundaries. :param bounding_rect: Input bounding rectangle (x,y,w,h) :type bounding_rect: cv2.boundingRect :param image_width: Image width :type image_width: int :param image_height: Image height :type image_height: int :return: Clamped bounding rectangle :rtype: cv2.boundingRect .. py:function:: rect_outside_image(bounding_rect: cv2.typing.Rect, image_width: int, image_height: int) Check whether a bounding rectangle is completely outside an image. A bounding rectangle is considered outside if it has no overlapping area with the image. Rectangles that only touch the image border (zero-area intersection) are treated as outside. :param bounding_rect: Bounding rectangle to check (x, y, w, h) :type bounding_rect: CV2.BoundingRect :param image_width: Image width :type image_width: int :param image_height: Image height :type image_height: int :return: True if the bounding rectangle lies completely outside the image, False otherwise :rtype: bool .. py:function:: sanity_checks_bounding_rects(bounding_rect: cv2.typing.Rect, 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. :param bounding_rect: Bounding rectangle to check (x,y,w,h) :type bounding_rect: cv2.boundingRect :param image_width: Image width :type image_width: int :param image_height: Image height :type image_height: int :return: True if rules have been passed, False otherwise :rtype: bool .. py:function:: 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. :param image: The image (OpenCV format). :type image: npt.NDArray :param roi: A tuple (x, y, width, height) representing the bounding box. :type roi: tuple :param offset: The amount by which to grow or shrink the ROI (can be negative). :type offset: int :return: A tuple (new_x, new_y, new_width, new_height) representing the adjusted ROI. :rtype: tuple .. py:function:: 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. :param image: The image this ROI is relative to. Necessary to respect the boundaries properly. :type image: npt.NDArray :param image_roi: An object of type ImageROI. :type image_roi: robokudo.types.cv.ImageROI :param offset: The amount by which to grow or shrink the ROI (can be negative). :type offset: int :return: None. The ImageROI's ROI is adjusted in place. .. py:function:: 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. :param mask: The mask corresponding to the ROI (same dimensions as the ROI). :type mask: npt.NDArray :param offset: The amount by which to grow or shrink the mask (can be negative). :type offset: int :param fill_value: The value to fill new areas when expanding the mask. :type fill_value: int :return: The adjusted mask. :rtype: npt.NDArray