robot_detect.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 # coding=utf-8
00003 
00004 __author__ = 'Minglong Li'
00005 
00006 import rospy
00007 import cv2
00008 import numpy as np
00009 from cv_bridge import CvBridge
00010 from sensor_msgs.msg import Image
00011 
00012 class Robot_detect(object):
00013     br = CvBridge()
00014     count = 0
00015     def __init__(self, name):
00016         sub = rospy.Subscriber("image", Image, self.image_cb)
00017     def image_cb(self, msg):
00018         im = self.br.imgmsg_to_cv2(msg, desired_encoding='passthrough')
00019         #print im
00020         for i in range(0, im.shape[0]):
00021             for j in range(0, im.shape[1]):
00022                 if im[i, j, 0] == 255 and im[i, j, 1] == 0 and im[i, j, 2] == 0:
00023                     print 'Detect an intruder!' 
00024 
00025 if __name__ == '__main__':
00026     rospy.init_node('robot_detect')
00027     robot_detect = Robot_detect(rospy.get_name())
00028     rospy.spin()
00029 
00030 
00031 


micros_mars_task_alloc
Author(s): Minglong Li , Xiaodong Yi , Yanzhen Wang , Zhongxuan Cai
autogenerated on Mon Jul 1 2019 19:55:03