plus_local.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 # Copyright (c) 2009, Willow Garage, Inc.
4 # All rights reserved.
5 #
6 # Redistribution and use in source and binary forms, with or without
7 # modification, are permitted provided that the following conditions are met:
8 #
9 # * Redistributions of source code must retain the above copyright
10 # notice, this list of conditions and the following disclaimer.
11 # * Redistributions in binary form must reproduce the above copyright
12 # notice, this list of conditions and the following disclaimer in the
13 # documentation and/or other materials provided with the distribution.
14 # * Neither the name of the Willow Garage, Inc. nor the names of its
15 # contributors may be used to endorse or promote products derived from
16 # this software without specific prior written permission.
17 #
18 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
21 # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
22 # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
23 # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
24 # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
25 # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
26 # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
27 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
28 # POSSIBILITY OF SUCH DAMAGE.
29 
30 
31 import roslib; roslib.load_manifest('test_nodelet')
32 import rospy
33 from std_msgs.msg import Float64
34 import unittest
35 import rostest
36 import random
37 
38 class PlusTester:
39  def __init__(self, topic_in, topic_out, delta):
40  self.pub = rospy.Publisher(topic_in, Float64)
41  self.sub = rospy.Subscriber(topic_out, Float64, self.callback)
42  self.expected_delta = delta
43  self.send_value = random.random()
44  self.recieved = False
45  self.result = False
46  self.delta = delta
47 
48  def run(self, cycles = 10):
49  for i in range(1, cycles):
50  self.pub.publish(Float64(self.send_value))
51  rospy.loginfo("Sent %f"%self.send_value);
52  if self.recieved == True:
53  break
54  rospy.sleep(1.0)
55  return self.result
56 
57  def callback(self, data):
58  rospy.loginfo(rospy.get_name()+" I heard %s which was a change of %f",data.data, data.data-self.send_value)
59  if data.data == self.send_value + self.delta:
60  self.result = True
61  self.recieved = True
62 
63 class TestPlus(unittest.TestCase):
64  def test_param(self):
65  pb = PlusTester("Plus/in", "Plus/out", 2.1)
66  self.assertTrue(pb.run())
67 
68  def test_default_param(self):
69  pb = PlusTester("Plus2/in", "Plus2/out", 10.0)
70  self.assertTrue(pb.run())
71 
72  def test_standalone(self):
73  pb = PlusTester("Plus2/out", "Plus3/out", 2.5)
74  self.assertTrue(pb.run())
75 
76  def test_remap(self):
77  pb = PlusTester("plus_remap/in", "remapped_output", 2.1)
78  self.assertTrue(pb.run())
79 
80  def test_chain(self):
81  pb = PlusTester("Plus2/in", "Plus3/out", 12.5)
82  self.assertTrue(pb.run())
83 
84 if __name__ == '__main__':
85  rospy.init_node('plus_local')
86  rostest.unitrun('test_nodelet', 'test_plus', TestPlus)
87 
def test_standalone(self)
Definition: plus_local.py:72
def test_remap(self)
Definition: plus_local.py:76
def test_chain(self)
Definition: plus_local.py:80
def test_param(self)
Definition: plus_local.py:64
def run(self, cycles=10)
Definition: plus_local.py:48
def test_default_param(self)
Definition: plus_local.py:68
def callback(self, data)
Definition: plus_local.py:57
def __init__(self, topic_in, topic_out, delta)
Definition: plus_local.py:39


test_nodelet
Author(s): Tully Foote
autogenerated on Mon Feb 18 2019 03:26:50