在計算機視覺中,顏色提取是一種常用的圖像處理技術,其中HSV(色相、飽和度、明度)是一種常見的顏色空間,用于描述和提取圖像中的顏色信息。
HSV顏色空間將顏色表示為三個分量:色相(H)、飽和度(S)和明度(V)。
?色相(Hue):色相是顏色的類型或類別,描述了顏色在光譜中的位置。在HSV模型中,色相表示為一個角度值,通常在0到360度之間,將整個顏色光譜分為不同的顏色區域,如紅、橙、黃、綠、藍、紫等。
?飽和度(Saturation):飽和度表示顏色的純度或強度,即顏色的深淺程度。飽和度為0時,顏色變為灰階;飽和度為最大值時,顏色呈現出最鮮艷的狀態。飽和度的取值范圍通常在0到1之間,也可以表示為0%到100%。
?明度(Value):明度表示顏色的明亮度,即顏色的亮度和深度。明度為0時,顏色為黑色;明度為最大值時,顏色為白色。明度的取值范圍通常在0到1之間,也可以表示為0%到100%。
通過這三個參數的組合,可以在HSV模型中精確地描述各種顏色,使得調整和理解顏色更加直觀和容易。在圖像處理中,HSV模型常用于調整圖像的顏色平衡、色調和亮度等方面。
硬件環境
操作環境及軟硬件配置如下:
?PC:Ubuntu (≥20.04) + ROS2 (≥Foxy)
代碼
import cv2
import numpy as np
import rclpy
from rclpy.node import Node
from sensor_msgs.msg import Image
from cv_bridge import CvBridge
from collections import deque
import textwrap
class GetHsv(Node):
def __init__(self):
super().__init__('get_hsv')
self.get_logger().info("Start get HSV")
self.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.count = 0
self.box_width = 60
self.collect_times = 300
self.HSV_value = deque(maxlen=self.collect_times)
self.H_range, self.S_range, self.V_range = 10, 80, 80
self.lower_HSV = None
self.upper_HSV = None
def image_callback(self, msg):
image = self.bridge.imgmsg_to_cv2(msg, 'bgr8')
if self.count < self.collect_times:
self.draw_rectangle(image)
elif self.count < self.collect_times + self.collect_times:
self.collect_hsv_value(image)
else:
self.save_hsv_value(image)
self.count += 1
self.pub.publish(self.bridge.cv2_to_imgmsg(image, 'bgr8'))
def draw_rectangle(self, image):
text = 'please put the color being tested in the rectangle box!'
self.add_text(image, text)
rect_x = (image.shape[1] - self.box_width) // 2
rect_y = (image.shape[0] - self.box_width) // 2
cv2.rectangle(image, (rect_x, rect_y), (
rect_x + self.box_width, rect_y + self.box_width), (0, 255, 0), 3)
def collect_hsv_value(self, image):
text = 'HSV_value is collecting!'
self.add_text(image, text)
frame_x = (image.shape[1] - self.box_width) // 2
frame_y = (image.shape[0] - self.box_width) // 2
frame = image[frame_y:frame_y + self.box_width, frame_x:frame_x + self.box_width]
self.HSV_value.append(self.calculate_mean_hsv(frame))
def save_hsv_value(self, image):
text = 'HSV_value is collected!'
self.add_text(image,text)
mean_HSV = np.mean(self.HSV_value, axis=0)
self.lower_HSV, self.upper_HSV = self.calculate_hsv_range(mean_HSV)
self.write_hsv_to_file(self.lower_HSV, self.upper_HSV)
def calculate_mean_hsv(self, img):
hsv_image = cv2.cvtColor(img, cv2.COLOR_BGR2HSV)
return np.mean(hsv_image, axis=(0, 1))
def calculate_hsv_range(self, HSV_value):
lower_H = np.clip(int(HSV_value[0] - self.H_range), 0, 180)
upper_H = np.clip(int(HSV_value[0] + self.H_range), 0, 180)
lower_S = np.clip(int(HSV_value[1] - self.S_range), 40, 255)
upper_S = np.clip(int(HSV_value[1] + self.S_range), 40, 255)
lower_V = np.clip(int(HSV_value[2] - self.V_range), 40, 255)
upper_V = np.clip(int(HSV_value[2] + self.V_range), 40, 255)
return np.array([lower_H, lower_S, lower_V]), np.array([upper_H, upper_S, upper_V])
def write_hsv_to_file(self, lower_HSV, upper_HSV):
content = f"block_HSV is : {lower_HSV[0]},
{lower_HSV[1]},{lower_HSV[2]} {upper_HSV[0]},{upper_HSV[1]},{upper_HSV[2]}
"
filename = "/userdata/dev_ws/color_block_HSV.txt"
with open(filename, "w+") as f:
f.write(content)
self.get_logger().info(f"HSV value has been saved in {filename}")
self.get_logger().info(content)
def add_text(self, image, text):
text = textwrap.wrap(text, width = 80)
text_y = image.shape[0] // 2 - 30
for line in text:
text_size, _ = cv2.getTextSize(line, cv2.FONT_HERSHEY_SIMPLEX, 1.2, 2)
text_x = (image.shape[1] - text_size[0]) // 2
cv2.putText(image, line, (text_x, text_y),
cv2.FONT_HERSHEY_SIMPLEX, 1.2, (0, 255, 0), 2, cv2.LINE_AA)
def main(args=None):
rclpy.init(args=args)
get_hsv = GetHsv()
rclpy.spin(get_hsv)
get_hsv.destroy_node()
rclpy.shutdown()
if __name__ == '__main__':
main()
簡要說明
這段代碼的作用是通過將相機對準你希望捕捉的圖像HSV值,進行一輪采集后便會將采集的HSV值存放在指定路徑了。
1、為什么要做HSV值獲取,HSV色彩空間相對于rgb色域有什么有特殊點嗎?
簡單來說,HSV色彩空間相對于RGB色域更符合人類對顏色的感知方式,更方便地進行顏色處理和分析,并且提供了更直觀和靈活的顏色定義和比較方式。舉個例子,人描述一個顏色通常不會直接說它的rgb值,而是描述淡綠色,艷紅色等,而這正是HSV色彩空間描述的方式。
2、應用HSV時為什么通常使用upper、lower兩組數據?
使用兩組閾值的好處是可以更準確地定義要提取的顏色范圍,同時考慮到色調環的邊界情況。這樣可以避免顏色提取結果受到色調環邊界的影響,提高顏色提取的準確性和穩定性。
3、是否可以將圖像直接使用opencv做處理?
還需要解耦圖像信息,例如ROS的圖像需要使用CVBridge處理成Opencv能處理的圖片,又比如在處理NV12時,需要將Hbmem轉成常規opencv識別的nv12格式。但無一例外我們可以稱之為解耦了。
4、 HSV如何和RGB進行轉換呢?
首先,將HSV中的色相、飽和度和明度分別歸一化到區間[0, 1]。
歸一化的色相(H’):H' = H / 360
歸一化的飽和度(S’):S' = S / 100
歸一化的明度(V’):V' = V / 100
接下來,使用以下公式計算RGB值:
如果飽和度為0,則RGB值為灰度色:
R = G = B = V'
如果飽和度不為0,則使用以下公式:
C = V' * S'
X = C * (1 - |(H' mod 2) - 1|
m = V' - C
然后,根據色相的不同情況,計算最終的RGB值:
當0 <= H' < 1/6 時:(R', G', B') = (C, X, 0)
當 1/6 <= H' < 2/6 時:(R', G', B') = (X, C, 0)
當 2/6 <= H' < 3/6 時:(R', G', B') = (0, C, X)
當 3/6 <= H' < 4/6 時:(R', G', B') = (0, X, C)
當 4/6 <= H' < 5/6 時:(R', G', B') = (X, 0, C)
當 5/6 <= H' <= 1 時:(R', G', B') = (C, 0, X)
最后,將得到的RGB值映射到區間[0, 255]。
-
圖像處理
+關注
關注
27文章
1282瀏覽量
56638 -
計算機視覺
+關注
關注
8文章
1696瀏覽量
45927 -
HSV
+關注
關注
0文章
10瀏覽量
2596
原文標題:ROS2 HSV值獲取
文章出處:【微信號:vision263com,微信公眾號:新機器視覺】歡迎添加關注!文章轉載請注明出處。
發布評論請先 登錄
相關推薦
評論