8 from sensor_msgs.msg
import Image
10 from image_view2.msg
import MouseEvent
14 pub_plus = rospy.Publisher(
'~plus_rect_event', MouseEvent, queue_size=1)
15 pub_minus = rospy.Publisher(
'~minus_rect_event', MouseEvent, queue_size=1)
17 width = rospy.get_param(
'~image_width')
18 height = rospy.get_param(
'~image_height')
20 MouseEvent(type=3, x=width/4, y=height/4, width=width, height=height),
21 MouseEvent(type=4, x=width/2, y=height/2, width=width, height=height),
22 MouseEvent(type=2, x=3*width/4, y=3*height/4, width=width, height=height),
25 MouseEvent(type=3, x=3*width/4, y=3*height/4, width=width, height=height),
26 MouseEvent(type=4, x=width/2, y=height/2, width=width, height=height),
27 MouseEvent(type=2, x=width/4, y=height/4, width=width, height=height),
30 while not rospy.is_shutdown():
32 e.header.stamp = rospy.get_rostime()
35 for e
in minus_events:
36 e.header.stamp = rospy.get_rostime()
41 if __name__ ==
'__main__':
42 rospy.init_node(
'publish_mouse_event')