-
Notifications
You must be signed in to change notification settings - Fork 29
/
color_contours.py
executable file
·62 lines (49 loc) · 1.86 KB
/
color_contours.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
#!/usr/bin/env python
import rospy
import cv2
import numpy
from sensor_msgs.msg import Image
from cv_bridge import CvBridge, CvBridgeError
class image_converter:
def __init__(self):
cv2.startWindowThread()
self.bridge = CvBridge()
# self.image_sub = rospy.Subscriber("/camera/image_raw",
# Image, self.callback)
self.image_sub = rospy.Subscriber("/camera/rgb/image_raw",
Image, self.callback)
def callback(self, data):
cv2.namedWindow("Image window", 1)
try:
cv_image = self.bridge.imgmsg_to_cv2(data, "bgr8")
except CvBridgeError, e:
print e
bgr_thresh = cv2.inRange(cv_image,
numpy.array((200, 230, 230)),
numpy.array((255, 255, 255)))
hsv_img = cv2.cvtColor(cv_image, cv2.COLOR_BGR2HSV)
hsv_thresh = cv2.inRange(hsv_img,
numpy.array((0, 150, 50)),
numpy.array((255, 255, 255)))
print numpy.mean(hsv_img[:, :, 0])
print numpy.mean(hsv_img[:, :, 1])
print numpy.mean(hsv_img[:, :, 2])
_, bgr_contours, hierachy = cv2.findContours(
bgr_thresh.copy(),
cv2.RETR_TREE,
cv2.CHAIN_APPROX_SIMPLE)
_, hsv_contours, hierachy = cv2.findContours(
hsv_thresh.copy(),
cv2.RETR_TREE,
cv2.CHAIN_APPROX_SIMPLE)
for c in hsv_contours:
a = cv2.contourArea(c)
if a > 100.0:
cv2.drawContours(cv_image, c, -1, (255, 0, 0), 3)
print '===='
cv2.imshow("Image window", cv_image)
cv2.waitKey(1)
image_converter()
rospy.init_node('image_converter', anonymous=True)
rospy.spin()
cv2.destroyAllWindows()