颜色识别

计算机视觉中的颜色识别是指计算机系统能够自动识别图像或视频中的不同颜色,以便进行分析、分类、跟踪和其他视觉任务。

颜色是物体的一个重要属性,它提供了有关对象的重要信息。

颜色识别在各种应用中都有重要作用,包括工业自动化、机器人技术、医学影像处理、安全监控、自动驾驶汽车、农业和许多其他领域。

硬件环境

操作环境及软硬件配置如下:

  • OriginBot 机器人
  • PC:Ubuntu (≥20.04) + ROS2 (≥Foxy)

代码

    #!/usr/bin/env python3
    # -*- coding: utf-8 -*-

    import rclpy
    import cv2
    import cv_bridge
    import numpy as np
    from rclpy.node import Node
    from sensor_msgs.msg import Image

    class ColorDetection(Node):
        def __init__(self):
            super().__init__('color_detection')
            self.bridge = cv_bridge.CvBridge()
            self.image_sub = self.create_subscription(Image, '/image_raw', self.image_callback, 10)
            self.pub = self.create_publisher(Image, '/camera/process_image', 10)
            self.load_hsv_values()
            self.area_max = 5


        def load_hsv_values(self):
            try:
                with open("/userdata/dev_ws/color_block_HSV.txt", "r") as file:
                    content = file.read()
                    import re
                    match = re.search(r'(\d+,\d+,\d+) (\d+,\d+,\d+)', content)
                    if match:
                        lower_hsv, upper_hsv = match.group(1).split(','), match.group(2).split(',')
                        self.hsv_lower = np.array([int(val) for val in lower_hsv], dtype=np.uint8)
                        self.hsv_upper = np.array([int(val) for val in upper_hsv], dtype=np.uint8)
                    else:
                        self.get_logger().error("Invalid format in HSV values file. Using default values.")
                        self.hsv_lower = np.array([2, 40, 40], dtype=np.uint8)
                        self.hsv_upper = np.array([22, 168, 190], dtype=np.uint8)
            except FileNotFoundError:
                self.get_logger().error("HSV values file not found. Using default values.")
                self.hsv_lower = np.array([2, 40, 40], dtype=np.uint8)
                self.hsv_upper = np.array([22, 168, 190], dtype=np.uint8)


        def image_callback(self, msg):
            image = self.bridge.imgmsg_to_cv2(msg, 'bgr8')
            hsv_img = cv2.cvtColor(image, cv2.COLOR_BGR2HSV)

            mask = cv2.inRange(hsv_img, self.hsv_lower, self.hsv_upper)
            kernel = np.ones((5, 5), np.uint8)
            mask = cv2.erode(mask, kernel)
            mask = cv2.dilate(mask, kernel)

            contours, _ = cv2.findContours(mask, cv2.RETR_EXTERNAL, cv2.CHAIN_APPROX_SIMPLE)
            contours = self.take_biggest_contours(contours)
            contours = self.agglomerative_cluster(contours)

            for cnt in contours:
                x, y, w, h = cv2.boundingRect(cnt)
                if w < 20 and h < 20:
                    continue
                cv2.rectangle(image, (x, y), (x + w, y + h), (0, 0, 255), 2)
                area = w * h
                if area > self.area_max:
                    self.area_max = area
                    cv2.imwrite("test.jpg", image)
                    self.get_logger().info("Image saved.")

            self.pub.publish(self.bridge.cv2_to_imgmsg(image, 'bgr8'))

        def take_biggest_contours(self, contours, max_number=20):
            sorted_contours = sorted(contours, key=lambda x: cv2.contourArea(x), reverse=True)
            return sorted_contours[:max_number]

        def calculate_contour_distance(self, contour1, contour2):
            x1, y1, w1, h1 = cv2.boundingRect(contour1)
            c_x1, c_y1 = x1 + w1 / 2, y1 + h1 / 2

            x2, y2, w2, h2 = cv2.boundingRect(contour2)
            c_x2, c_y2 = x2 + w2 / 2, y2 + h2 / 2

            return max(abs(c_x1 - c_x2) - (w1 + w2) / 2, abs(c_y1 - c_y2) - (h1 + h2) / 2)

        def agglomerative_cluster(self, contours, threshold_distance=100.0):
            current_contours = contours
            while len(current_contours) > 1:
                min_distance = None
                min_coordinate = None

                for x in range(len(current_contours) - 1):
                    for y in range(x + 1, len(current_contours)):
                        distance = self.calculate_contour_distance(
                                current_contours[x], current_contours[y])
                        if min_distance is None or distance < min_distance:
                            min_distance = distance
                            min_coordinate = (x, y)

                if min_distance is not None and min_distance < threshold_distance:
                    index1, index2 = min_coordinate
                    current_contours[index1] = np.concatenate(
                            [current_contours[index1], current_contours[index2]])
                    del current_contours[index2]
                else:
                    break
            return current_contours

    def main(args=None):
        rclpy.init(args=args)
        color_detection = ColorDetection()
        rclpy.spin(color_detection)
        color_detection.destroy_node()
        rclpy.shutdown()

    if __name__ == '__main__':
        main()

简要说明

本节内容为上一篇文章HSV值获取的后续,通过之前采集的HSV值便可以直接进行颜色识别了。

"""
从颜色提取中读到HSV颜色阈值
"""
def load_hsv_values(self):
    try:
        with open("/userdata/dev_ws/color_block_HSV.txt", "r") as file:
            content = file.read()
            import re                       #使用正则表达式读取文件中的HSV值,并将值转换为int类型
            match = re.search(r'(\d+,\d+,\d+) (\d+,\d+,\d+)', content)
            if match:
                lower_hsv, upper_hsv = match.group(1).split(','), match.group(2).split(',')
                self.hsv_lower = np.array([int(val) for val in lower_hsv], dtype=np.uint8)
                self.hsv_upper = np.array([int(val) for val in upper_hsv], dtype=np.uint8)
            else:
                self.get_logger().error("Invalid format in HSV values file. Using default values.")
                self.hsv_lower = np.array([2, 40, 40], dtype=np.uint8)
                self.hsv_upper = np.array([22, 168, 190], dtype=np.uint8)
    except FileNotFoundError:
        self.get_logger().error("HSV values file not found. Using default values.")
        self.hsv_lower = np.array([2, 40, 40], dtype=np.uint8)
        self.hsv_upper = np.array([22, 168, 190], dtype=np.uint8)

聚类是滤波很重要的一种方式,其作用类似于机器学习中交并比、NMS的作用,确保一个物体只有一个boundingBox进行框定。

"""
将接近的boundingBox聚类到一起
"""
def agglomerative_cluster(self, contours, threshold_distance=100.0):
    current_contours = contours
    while len(current_contours) > 1:
        min_distance = None
        min_coordinate = None

        for x in range(len(current_contours) - 1):
            for y in range(x + 1, len(current_contours)):
                distance = self.calculate_contour_distance(
                        current_contours[x], current_contours[y])
                if min_distance is None or distance < min_distance:
                    min_distance = distance
                    min_coordinate = (x, y)
        # min_distance(最短距离)不为零,并且小于阈值就进行拼接,并将更小的boundingBox删除 
        if min_distance is not None and min_distance < threshold_distance:
            index1, index2 = min_coordinate
            current_contours[index1] = np.concatenate(
                    [current_contours[index1], current_contours[index2]])
            del current_contours[index2]
        else:
            break
    return current_contours

什么情况下会使用这种方式进行颜色识别?如何确保效果稳定?

使用opencv进行颜色识别一般使用在周围环境并不复杂,且颜色相对来说单调的环境,且需要目标颜色在环境中较为明显。同时使用opencv HSV色域进行颜色识别会遇到光线影响导致颜色色彩变化大的问题,所以需要预留一定的空间给HSV阈值。