## page was renamed from diagnostic_aggregator/Tutorials/Adding Analyzers at Runtime ## For instruction on writing tutorials ## http://www.ros.org/wiki/WritingTutorials #################################### ##FILL ME IN #################################### ## for a custom note with links: ## note = ## for the canned note of "This tutorial assumes that you have completed the previous tutorials:" just add the links ## note.0= ## descriptive title for the tutorial ## title = Adding Analyzers at Runtime ## multi-line description to be displayed in search ## description = Use launch files or bonds and a service to add a new set of analyzers to the aggregator. ## the next tutorial description (optional) ## next = ## links to next tutorial (optional) ## next.0.link= ## next.1.link= ## what level user is this tutorial for ## level= IntermediateCategory ## keywords = #################################### <> <> <> == Overview == It is possible to modify what the diagnostic aggregator analyzes while it is running. This allows you to temporarily add diagnostic analyzers only when they are needed, to reduce clutter, or to add analyzers corresponding to a specific node or collection of nodes in a launch file so that they are added when the launch file is run. This has the added benefit of allowing you to separate analyzers based on which parts of the system they are analyzing. This tutorial will show you how to add analyzers either from a launch file or from inside a node. We will create a small test package to demonstrate the functionality. == Creating the Test Package == {{{ catkin_create_pkg test_add_analyzers diagnostic_msgs rospy roscpp bondpy }}} Create directories for launch files, scripts for diagnostic publishing, and parameters for analyzer setup. {{{ roscd test_add_analyzers mkdir launch scripts param }}} Add a launch file for the diagnostic aggregator. `launch/base.launch` {{{ }}} Add a node to publish some diagnostic messages. Don't forget to make it executable. `scripts/base_node.py` {{{#!python #!/usr/bin/env python import rospy from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus if __name__ == '__main__': rospy.init_node('base_node') pub = rospy.Publisher('/diagnostics', DiagnosticArray, queue_size=1) arr = DiagnosticArray() arr.status = [ DiagnosticStatus(name='battery battery_message', message='the battery message'), DiagnosticStatus(name='joystick joystick_message', message='the joystick message') ] rate = rospy.Rate(1) while not rospy.is_shutdown(): arr.header.stamp = rospy.Time.now() pub.publish(arr) rate.sleep() }}} Add a `.yaml` containing some simple analyzers. `param/base_analyzers.yaml` {{{ analyzers: base: type: diagnostic_aggregator/AnalyzerGroup path: Base analyzers: battery: type: diagnostic_aggregator/GenericAnalyzer path: Battery find_and_remove_prefix: 'battery' joy: type: diagnostic_aggregator/GenericAnalyzer path: Joystick find_and_remove_prefix: 'joystick' }}} == Loading From Launch Files == Loading from a launch file is done in a similar way to how the diagnostic aggregator is launched. Parameters defining the analyzers are loaded directly into the node namespace, which the aggregator then reads in order to initialise the new analyzers. The `add_analyzers` node is linked to the aggregator via a `bond` object. When the node is shut down, the bond breaks, and the analyzers associated with that node will be removed from the aggregator. The parameters which were loaded by the node are not deleted when the node shuts down. Add a launch file to add the analyzers. `launch/simple.launch` {{{ }}} Add a node to publish some dummy data to the diagnostics topic. Remember to make it executable. `scripts/simple_node.py` {{{#!python #!/usr/bin/env python import rospy from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus if __name__ == '__main__': rospy.init_node('simple_node') pub = rospy.Publisher('/diagnostics', DiagnosticArray, queue_size=1) arr = DiagnosticArray() arr.status = [ DiagnosticStatus(name='rgb_stream rgb_message', message='the rgb data'), DiagnosticStatus(name='rgbd_stream rgbd_message', message='the rgbd data') ] rate = rospy.Rate(1) while not rospy.is_shutdown(): arr.header.stamp = rospy.Time.now() pub.publish(arr) rate.sleep() }}} Add a `.yaml` for some different analyzer specifications. `param/simple_analyzers.yaml` {{{ analyzers: vision: type: diagnostic_aggregator/AnalyzerGroup path: Vision analyzers: rgb: type: diagnostic_aggregator/GenericAnalyzer path: CameraRGB find_and_remove_prefix: 'rgb_stream' rgbd: type: diagnostic_aggregator/GenericAnalyzer path: CameraRGBD find_and_remove_prefix: 'rgbd_stream' }}} First, launch the aggregator with the base analyzers using {{{ roslaunch test_add_analyzers base.launch }}} Then, run the `rqt_robot_monitor` to view the aggregator output. {{{ rosrun rqt_robot_monitor rqt_robot_monitor }}} Finally, add the simple analyzers to the aggregator output. {{{ roslaunch test_add_analyzers simple.launch }}} You should see the diagnostic output appear, first in the `Other` group, and then in the correct groups when the aggregator finishes updating the analyzers. == Loading From a Node == It is also possible to add analyzers to the aggregator from inside a node. Create a launcher for the node. `launch/manual_node.launch` {{{ }}} Add some analyzer parameters. `param/manual_analyzers.yaml` {{{ analyzers: buttons: type: diagnostic_aggregator/AnalyzerGroup path: Buttons analyzers: go_button: type: diagnostic_aggregator/GenericAnalyzer path: Go find_and_remove_prefix: 'button_go' stop_button: type: diagnostic_aggregator/GenericAnalyzer path: Stop find_and_remove_prefix: 'button_stop' }}} Add a node to publish diagnostics `scripts/manual_diag.py` {{{#!python #!/usr/bin/env python import rospy from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus if __name__ == '__main__': rospy.init_node('manual_diag') pub = rospy.Publisher('/diagnostics', DiagnosticArray, queue_size=1) arr = DiagnosticArray() arr.status = [ DiagnosticStatus(name='button_stop go_message', message='the go button message'), DiagnosticStatus(name='button_go stop_message', message='the stop button message') ] rate = rospy.Rate(1) while not rospy.is_shutdown(): arr.header.stamp = rospy.Time.now() pub.publish(arr) rate.sleep() }}} Add a node to do the additions. `scripts/manual_node.py` {{{#!python #!/usr/bin/env python import rospy import rosparam from bondpy import bondpy from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus from diagnostic_msgs.srv import AddDiagnostics class ManualNode(object): def __init__(self): rospy.init_node('manual') rospy.on_shutdown(self.shutdown) # Load yaml parameters from a file, and load them into the parameter server # under this node's namespace. paramlist = rosparam.load_file(rospy.get_param('~analyzer_yaml')) for params, ns in paramlist: rosparam.upload_params(rospy.get_name() + '/' + ns, params) # Can use any namespace into which the parameters that we want to use to # specify analyzers have been loaded self.namespace = rospy.get_name() def start(self): # Create a bond to try and connect to the diagnostics aggregator. The second # parameter to the bond is the name of the bond. This name should be the # same as the load_namespace below self.bond = bondpy.Bond("/diagnostics_agg/bond", rospy.resolve_name(self.namespace)) # Start the bond, initialising the connection and creating the analyzers # that were defined by the parameters loaded earlier self.bond.start() # To start the other side of the bond in the diagnostic aggregator, we must # send request via the add_diagnostics service. Once a service message is # received, the bond will form, and the analyzers will be added to the # aggregator. rospy.wait_for_service('/diagnostics_agg/add_diagnostics', timeout=10) add_diagnostics = rospy.ServiceProxy('/diagnostics_agg/add_diagnostics', AddDiagnostics) # The response indicates whether setup was successful or not. If the # namespace given is the same as a namespace that was sent previously, the # analyzers will not be added. resp = add_diagnostics(load_namespace=self.namespace) rate = rospy.Rate(1) while not rospy.is_shutdown(): rate.sleep() def shutdown(self): # Make sure the bond is shut down once you're done. If it is not shut down # manually, the other side of the bond will automatically shut down after a # short time (~5 seconds), removing the analyzers from the aggregator. self.bond.shutdown() if __name__ == '__main__': m = ManualNode() m.start() }}} Having launched the base aggregator, launch the node {{{ roslaunch test_add_analyzers manual_node.launch }}} ## AUTOGENERATED DO NOT DELETE ## TutorialCategory ## DiagnosticAggregatorCategory