publish_mouse_event.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 # -*- coding: utf-8 -*-
00003 
00004 import cv2
00005 import numpy as np
00006 from scipy.misc import lena
00007 
00008 import rospy
00009 from sensor_msgs.msg import Image
00010 import cv_bridge
00011 from image_view2.msg import MouseEvent
00012 
00013 
00014 def main():
00015     pub_plus = rospy.Publisher('~plus_rect_event', MouseEvent, queue_size=1)
00016     pub_minus = rospy.Publisher('~minus_rect_event', MouseEvent, queue_size=1)
00017 
00018     rospy.loginfo('Waiting for image_view2 launch..')
00019 
00020     width = rospy.get_param('~image_width')
00021     height = rospy.get_param('~image_height')
00022     plus_events = [
00023         MouseEvent(type=3, x=width/4, y=height/4, width=width, height=height),
00024         MouseEvent(type=4, x=width/2, y=height/2, width=width, height=height),
00025         MouseEvent(type=2, x=3*width/4, y=3*height/4, width=width, height=height),
00026     ]
00027     minus_events = [
00028         MouseEvent(type=3, x=3*width/4, y=3*height/4, width=width, height=height),
00029         MouseEvent(type=4, x=width/2, y=height/2, width=width, height=height),
00030         MouseEvent(type=2, x=width/4, y=height/4, width=width, height=height),
00031     ]
00032     rate = rospy.Rate(10)
00033     while not rospy.is_shutdown():
00034         for e in plus_events:
00035             e.header.stamp = rospy.get_rostime()
00036             pub_plus.publish(e)
00037             rate.sleep()
00038         for e in minus_events:
00039             e.header.stamp = rospy.get_rostime()
00040             pub_minus.publish(e)
00041             rate.sleep()
00042 
00043 
00044 if __name__ == '__main__':
00045     rospy.init_node('publish_lena')
00046     main()


image_view2
Author(s): Kei Okada
autogenerated on Fri Sep 8 2017 03:38:44