#!/usr/bin/env python from __future__ import print_function, division import cv2 import numpy as np import rospy from cv_bridge import CvBridge, CvBridgeError from sensor_msgs.msg import Image from std_msgs.msg import Float32 H_MIN, S_MIN, V_MIN = 0, 0, 0 H_MAX, S_MAX, V_MAX = 179, 255, 255 MIN_RADIUS_SIZE = 10 # Green Thresholds GREEN_LOWER = [29, 86, 6] GREEN_UPPER = [84, 255, 255] # Dummy callback for trackbar initialization def nothing(x): pass class FindColor: def __init__(self, debug=False): # Converter of ros image to opencv image self.bridge = CvBridge() # Subscribe to the camera #TODO # Create the center_deviation topic where we will publish the error #TODO # Create the ball_radius topic where we will publish the radius of the ball self.ball_radius_pub = rospy.Publisher('ball_radius', Float32, queue_size = 10) # Dummy images self.cv_image = np.zeros((100, 100, 3), np.uint8) self.hsv = np.zeros((100, 100, 3), np.uint8) # Init Thresholds self.h_min, self.s_min, self.v_min = GREEN_LOWER self.h_max, self.s_max, self.v_max = GREEN_UPPER self.debug = debug if debug: self.image_name, self.mask_name = "RGB", "Mask" # Create Windows cv2.namedWindow(self.image_name) cv2.namedWindow(self.mask_name) cv2.waitKey(1000) # Creating track bar for min_max in ['min', 'max']: cv2.createTrackbar('h_{}'.format(min_max), self.mask_name, H_MIN, H_MAX, nothing) cv2.createTrackbar('s_{}'.format(min_max), self.mask_name, S_MIN, S_MAX, nothing) cv2.createTrackbar('v_{}'.format(min_max), self.mask_name, V_MIN, V_MAX, nothing) # Initial value, for green cv2.setTrackbarPos('h_min', self.mask_name, self.h_min) cv2.setTrackbarPos('s_min', self.mask_name, self.s_min) cv2.setTrackbarPos('v_min', self.mask_name, self.v_min) cv2.setTrackbarPos('h_max', self.mask_name, self.h_max) cv2.setTrackbarPos('s_max', self.mask_name, self.s_max) cv2.setTrackbarPos('v_max', self.mask_name, self.v_max) def callback(self, data): try: self.cv_image = self.bridge.imgmsg_to_cv2(data, "bgr8") except CvBridgeError as e: print("Error converting the image: {}".format(e)) return if self.debug: # Get info from track bar and appy to result self.h_min = cv2.getTrackbarPos('h_min', self.mask_name) self.s_min = cv2.getTrackbarPos('s_min', self.mask_name) self.v_min = cv2.getTrackbarPos('v_min', self.mask_name) self.h_max = cv2.getTrackbarPos('h_max', self.mask_name) self.s_max = cv2.getTrackbarPos('s_max', self.mask_name) self.v_max = cv2.getTrackbarPos('v_max', self.mask_name) # Convert to HSV color space self.hsv = cv2.cvtColor(self.cv_image, cv2.COLOR_RGB2HSV) mask, center, radius = None, None, 0 # If valid values update the Thresholds if self.h_min <= self.h_max and self.s_min <= self.s_max and self.v_min <= self.v_max: lower = np.array([self.h_min, self.s_min, self.v_min]) upper = np.array([self.h_max, self.s_max, self.v_max]) # Create the binary mask mask = cv2.inRange(self.hsv, lower, upper) # Erosion and dilation to remove noise kernel = np.ones((7, 7), np.uint8) mask = cv2.erode(mask, kernel, iterations=2) mask = cv2.dilate(mask, kernel, iterations=2) # Find contours in the mask contours = cv2.findContours(mask.copy(), cv2.RETR_EXTERNAL, cv2.CHAIN_APPROX_SIMPLE)[-2] if len(contours) > 0: # Find largest contour and compute the minimum enclosing circle c = max(contours, key=cv2.contourArea) ((x, y), radius) = cv2.minEnclosingCircle(c) # Compute the centroid of the mask M = cv2.moments(c) center = (int(M["m10"] / M["m00"]), int(M["m01"] / M["m00"])) else: pass # print("No center found") else: print("Invalid values for Thresholds") # Create the masked image self.mask_image = cv2.bitwise_and(self.cv_image, self.cv_image, mask=mask) # Only proceed if the radius meets a minimum size if radius > MIN_RADIUS_SIZE and self.debug: # Draw the enclosing circle and center on the two images cv2.circle(self.mask_image, (int(x), int(y)), int(radius), (0, 255, 255), 2) cv2.circle(self.mask_image, center, 5, (0, 0, 255), -1) cv2.circle(self.cv_image, (int(x), int(y)), int(radius), (0, 255, 255), 2) cv2.circle(self.cv_image, center, 5, (0, 0, 255), -1) # Publish deviation from the middle of the image (= the error) if center is not None: # print("Center found: {}".format(center)) # center_deviation_px = int(center[0] - image_width // 2) # Rescale the error to [-1, 1] image_width = self.cv_image.shape[1] max_deviation = image_width // 2 center_deviation = (center[0] - max_deviation) / max_deviation # print("Center deviation : {}".format(center_deviation)) # Publish the error to the corresponding topic #TODO # Publish the ball_radius if radius > MIN_RADIUS_SIZE: self.ball_radius_pub.publish(radius) if self.debug: # Show the images cv2.imshow(self.image_name, self.cv_image) cv2.imshow(self.masked, self.mask_image) # Wait 3 ms to show the images cv2.waitKey(3) if __name__ == '__main__': print("Starting FindColor node") rospy.init_node('FindColor', anonymous=True) ic = FindColor() try: rospy.spin() except KeyboardInterrupt: print("Shutting down") cv2.destroyAllWindows()