source.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 # Software License Agreement (BSD License)
3 #
4 # Copyright (c) 2008, Willow Garage, Inc.
5 # Copyright (c) 2016, Tal Regev.
6 # All rights reserved.
7 #
8 # Redistribution and use in source and binary forms, with or without
9 # modification, are permitted provided that the following conditions
10 # are met:
11 #
12 # * Redistributions of source code must retain the above copyright
13 # notice, this list of conditions and the following disclaimer.
14 # * Redistributions in binary form must reproduce the above
15 # copyright notice, this list of conditions and the following
16 # disclaimer in the documentation and/or other materials provided
17 # with the distribution.
18 # * Neither the name of the Willow Garage nor the names of its
19 # contributors may be used to endorse or promote products derived
20 # from this software without specific prior written permission.
21 #
22 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 # POSSIBILITY OF SUCH DAMAGE.
34 
35 import sys
36 import time
37 import math
38 import rospy
39 import numpy
40 import cv2
41 
42 import sensor_msgs.msg
43 from cv_bridge import CvBridge
44 
45 
46 # Send black pic with a circle as regular and compressed ros msgs.
47 class Source:
48 
49  def __init__(self):
50  self.pub = rospy.Publisher("/opencv_tests/images", sensor_msgs.msg.Image)
51  self.pub_compressed = rospy.Publisher("/opencv_tests/images/compressed", sensor_msgs.msg.CompressedImage)
52 
53  def spin(self):
54  time.sleep(1.0)
55  started = time.time()
56  counter = 0
57  cvim = numpy.zeros((480, 640, 1), numpy.uint8)
58  ball_xv = 10
59  ball_yv = 10
60  ball_x = 100
61  ball_y = 100
62 
63  cvb = CvBridge()
64 
65  while not rospy.core.is_shutdown():
66 
67  cvim.fill(0)
68  cv2.circle(cvim, (ball_x, ball_y), 10, 255, -1)
69 
70  ball_x += ball_xv
71  ball_y += ball_yv
72  if ball_x in [10, 630]:
73  ball_xv = -ball_xv
74  if ball_y in [10, 470]:
75  ball_yv = -ball_yv
76 
77  self.pub.publish(cvb.cv2_to_imgmsg(cvim))
78  self.pub_compressed.publish(cvb.cv2_to_compressed_imgmsg(cvim))
79  time.sleep(0.03)
80 
81 
82 def main(args):
83  s = Source()
84  rospy.init_node('Source')
85  try:
86  s.spin()
87  rospy.spin()
88  outcome = 'test completed'
89  except KeyboardInterrupt:
90  print "shutting down"
91  outcome = 'keyboard interrupt'
92  rospy.core.signal_shutdown(outcome)
93 
94 if __name__ == '__main__':
95  main(sys.argv)
def spin(self)
Definition: source.py:53
def main(args)
Definition: source.py:82
def __init__(self)
Definition: source.py:49


opencv_tests
Author(s): James Bowman
autogenerated on Thu Dec 12 2019 03:52:13