File: add_analyzers_test.py

package info (click to toggle)
ros-diagnostics 1.10.1%2Bds1-3
  • links: PTS, VCS
  • area: main
  • in suites: bullseye
  • size: 1,316 kB
  • sloc: cpp: 2,995; python: 2,456; xml: 225; sh: 20; makefile: 3
file content (137 lines) | stat: -rwxr-xr-x 5,941 bytes parent folder | download
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
#!/usr/bin/env python3
# Software License Agreement (BSD License)
#
# Copyright (c) 2009, Willow Garage, Inc.
# All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
#  * Redistributions of source code must retain the above copyright
#    notice, this list of conditions and the following disclaimer.
#  * Redistributions in binary form must reproduce the above
#    copyright notice, this list of conditions and the following
#    disclaimer in the documentation and/or other materials provided
#    with the distribution.
#  * Neither the name of the Willow Garage nor the names of its
#    contributors may be used to endorse or promote products derived
#    from this software without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#

import unittest
import rospy, rostest
import rosparam
import optparse
import sys
import threading
from bondpy import bondpy
from diagnostic_msgs.srv import AddDiagnostics
from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus

PKG = 'diagnostic_aggregator'

class TestAddAnalyzer(unittest.TestCase):
    def __init__(self, *args):
        super(TestAddAnalyzer, self).__init__(*args)
        rospy.init_node('test_add_analyzer')
        self.namespace = rospy.get_name()
        paramlist = rosparam.load_file(rospy.myargv()[1])
        # expect to receive these paths in the added analyzers
        self.expected = [paramlist[0][1] + analyzer['path'] for name, analyzer in paramlist[0][0]['analyzers'].items()]

        self._mutex = threading.Lock()
        self.agg_msgs = {}

        # put parameters in the node namespace so they can be read by the aggregator
        for params, ns in paramlist:
            rosparam.upload_params(rospy.get_name() + '/' + ns, params)

        rospy.Subscriber('/diagnostics_agg', DiagnosticArray, self.agg_cb)
        self.pub = rospy.Publisher('/diagnostics', DiagnosticArray, queue_size=1)

    def agg_cb(self, msg):
        with self._mutex:
            for stat in msg.status:
                self.agg_msgs[stat.name] = stat

    def add_analyzer(self):
        """Start a bond to the aggregator
        """
        namespace = rospy.resolve_name(rospy.get_name())
        self.bond = bondpy.Bond("/diagnostics_agg/bond" + namespace, namespace)
        self.bond.start()
        rospy.wait_for_service('/diagnostics_agg/add_diagnostics', timeout=10)
        add_diagnostics = rospy.ServiceProxy('/diagnostics_agg/add_diagnostics', AddDiagnostics)
        print(self.namespace)
        resp = add_diagnostics(load_namespace=self.namespace)
        self.assert_(resp.success, 'Service call was unsuccessful: {0}'.format(resp.message))

    def wait_for_agg(self):
        self.agg_msgs = {}
        while not self.agg_msgs and not rospy.is_shutdown():
            rospy.sleep(rospy.Duration(3))

    def test_add_agg(self):
        self.wait_for_agg()

        # confirm that the things we're going to add aren't there already
        with self._mutex:
            agg_paths = [msg.name for name, msg in self.agg_msgs.items()]
            self.assert_(not any(expected in agg_paths for expected in self.expected))
            
        # add the new groups
        self.add_analyzer()

        arr = DiagnosticArray()
        arr.header.stamp = rospy.get_rostime()
        arr.status = [
            DiagnosticStatus(name='primary', message='hello-primary'),
            DiagnosticStatus(name='secondary', message='hello-secondary')
        ]
        self.pub.publish(arr)
        self.wait_for_agg()
        # the new aggregator data should contain the extra paths. At this point
        # the paths are probably still in the 'Other' group because the bond
        # hasn't been fully formed
        with self._mutex:
            agg_paths = [msg.name for name, msg in self.agg_msgs.items()]
            self.assert_(all(expected in agg_paths for expected in self.expected))

        rospy.sleep(rospy.Duration(5)) # wait a bit for the new items to move to the right group
        arr.header.stamp = rospy.get_rostime()
        self.pub.publish(arr) # publish again to get the correct groups to show OK
        self.wait_for_agg()

        for name, msg in self.agg_msgs.items():
            if name in self.expected: # should have just received messages on the analyzer
                self.assert_(msg.message == 'OK')
                
            agg_paths = [msg.name for name, msg in self.agg_msgs.items()]
            self.assert_(all(expected in agg_paths for expected in self.expected))
                

        self.bond.shutdown()
        rospy.sleep(rospy.Duration(5)) # wait a bit for the analyzers to unload
        self.wait_for_agg()
        # the aggregator data should no longer contain the paths once the bond is shut down
        with self._mutex:
            agg_paths = [msg.name for name, msg in self.agg_msgs.items()]
            self.assert_(not any(expected in agg_paths for expected in self.expected))
        
if __name__ == '__main__':
    print('SYS ARGS:', sys.argv)
    rostest.run(PKG, sys.argv[0], TestAddAnalyzer, sys.argv)