11#!/usr/bin/env python
22from __future__ import print_function
33
4- import roslib
54import sys
6- import rospy
5+
76import cv2
7+ import numpy as np
8+ import rospy
9+ import roslib
810from std_msgs .msg import String
911from sensor_msgs .msg import Image
1012from cv_bridge import CvBridge , CvBridgeError
11- import numpy as np
1213
1314from color_object_detection .msg import Rectangle
1415
15- class image_converter :
16+ class ImageConverter :
1617
1718 def __init__ (self ):
18- self .image_pub = rospy .Publisher ("/camera/color/image_raw/segmented " ,Image , queue_size = 10 )
19- self .bbox_pub = rospy .Publisher ("/bbox" , Rectangle , queue_size = 1000 )
19+ self .image_pub = rospy .Publisher ("/object_detection/image_segmented " ,Image , queue_size = 10 )
20+ self .bbox_pub = rospy .Publisher ("/object_detection/ bbox" , Rectangle , queue_size = 100 )
2021
2122 self .bridge = CvBridge ()
22- self .image_sub = rospy .Subscriber ("/camera/color/image_raw" ,Image ,self .callback )
23+ self .image_sub = rospy .Subscriber ("/camera/color/image_raw" , Image , self .callback )
2324
2425 def callback (self ,data ):
2526 try :
@@ -31,39 +32,40 @@ def callback(self,data):
3132 hsv_image = cv2 .cvtColor (cv_image , cv2 .COLOR_BGR2HSV )
3233
3334 # define range of blue color in HSV
34- lower_red1 = np .array ([0 ,50 ,100 ])
35- upper_red1 = np .array ([10 ,255 ,255 ])
35+ lower_red1 = np .array ([0 , 50 , 100 ])
36+ upper_red1 = np .array ([10 , 255 , 255 ])
3637
37- lower_red2 = np .array ([175 ,50 ,100 ])
38- upper_red2 = np .array ([180 ,255 ,255 ])
38+ lower_red2 = np .array ([175 , 50 , 100 ])
39+ upper_red2 = np .array ([180 , 255 , 255 ])
3940
4041 # Threshold the HSV image to get only blue colors
4142 mask1 = cv2 .inRange (hsv_image , lower_red1 , upper_red1 )
4243 mask2 = cv2 .inRange (hsv_image , lower_red2 , upper_red2 )
4344 mask = cv2 .bitwise_or (mask1 ,mask2 )
44- kernel = np .ones ((5 ,5 ),np .uint8 )
45+ kernel = np .ones ((5 , 5 ), np .uint8 )
4546
46- mask = cv2 .erode (mask ,kernel ,iterations = 2 )
47- mask = cv2 .dilate (mask ,kernel ,iterations = 2 )
47+ mask = cv2 .erode (mask , kernel , iterations = 2 )
48+ mask = cv2 .dilate (mask , kernel , iterations = 2 )
4849
49- ret ,thresh = cv2 .threshold (mask ,200 ,255 ,0 )
50+ ret ,thresh = cv2 .threshold (mask , 200 , 255 , 0 )
5051 im , contours ,hierarchy = cv2 .findContours (thresh , 1 , 2 )
5152
5253 c = max (contours , key = cv2 .contourArea )
5354
5455 cnt = contours [0 ]
55- x ,y , w , h = cv2 .boundingRect (c )
56+ x , y , w , h = cv2 .boundingRect (c )
5657
5758 # Bitwise-AND mask and original image
5859 # res1 = cv2.bitwise_and(cv_image,cv_image, mask= mask1)
5960 # res2 = cv2.bitwise_and(cv_image,cv_image, mask= mask2)
6061 # res = cv2.bitwise_or(res1, res2)
6162
62- rect = Rectangle (x ,y ,x + w ,y + h )
63+ d = 10
64+ rect = Rectangle (x - d , y - d , x + w + d , y + h + d )
6365 self .bbox_pub .publish (rect )
6466
65- res = cv2 .bitwise_and (cv_image ,cv_image , mask = mask )
66- cv2 .rectangle (res ,( x , y ),( x + w , y + h ), (0 ,255 ,0 ),2 )
67+ res = cv2 .bitwise_and (cv_image , cv_image , mask = mask )
68+ cv2 .rectangle (res , ( x - d , y - d ), ( x + w + d , y + h + d ), (0 , 255 , 0 ), 2 )
6769
6870 # cv2.imshow("Image window", res)
6971 # cv2.waitKey(3)
@@ -74,8 +76,8 @@ def callback(self,data):
7476 print (e )
7577
7678def main (args ):
77- rospy .init_node ('image_converter ' , anonymous = True )
78- ic = image_converter ()
79+ rospy .init_node ('object_detector ' , anonymous = True )
80+ ic = ImageConverter ()
7981
8082 try :
8183 rospy .spin ()
@@ -84,4 +86,4 @@ def main(args):
8486 cv2 .destroyAllWindows ()
8587
8688if __name__ == '__main__' :
87- main (sys .argv )
89+ main (sys .argv )
0 commit comments