ssm_introspection.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 #
00003 # Copyright 2015 Airbus
00004 # Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
00005 #
00006 # Licensed under the Apache License, Version 2.0 (the "License");
00007 # you may not use this file except in compliance with the License.
00008 # You may obtain a copy of the License at
00009 #
00010 #   http://www.apache.org/licenses/LICENSE-2.0
00011 #
00012 # Unless required by applicable law or agreed to in writing, software
00013 # distributed under the License is distributed on an "AS IS" BASIS,
00014 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00015 # See the License for the specific language governing permissions and
00016 # limitations under the License.
00017 
00018 from std_msgs.msg import String, Empty
00019 
00020 import threading
00021 import smach
00022 import rospy
00023 import airbus_ssm_core.msg
00024 from ast import literal_eval
00025 
00026 
00027 class ssmIntrospection():
00028     def __init__(self, state_machine, action_server = None):
00029         """Traverse the smach tree starting at root, and construct introspection
00030         proxies for getting and setting debug state."""
00031 
00032         self._state_machine = state_machine
00033         self._as = action_server
00034         self._tree_view = {}
00035         self._server_name = rospy.get_param('ssm_server_name', '/ssm')
00036         self._update_pub = rospy.Publisher(self._server_name + "/ssm_status", String, queue_size = 1)
00037         self._request_update = rospy.Subscriber(self._server_name + "/status_request", Empty, self._status_request_cb, queue_size = 1)
00038 
00039     def start(self):
00040         # Construct proxies
00041         self._state_machine._create_tree_view()
00042         self.construct(self._state_machine,"ROOT")
00043     
00044     def stop(self):
00045         self._request_update.unregister()
00046         self._tree_view = {}
00047         
00048 
00049     def construct(self, state, _key):
00050         """Recursively construct tree view."""
00051         self._tree_view[_key] = state.get_tree_view()
00052         state.register_tree_view_cb(self._update_tree_view_cb)
00053         # Get a list of children that are also containers
00054         for (label, child) in state.get_children().items():
00055             # If this is also a container, recurse into it
00056             if isinstance(child, smach.container.Container):
00057                 child._create_tree_view()
00058                 self.construct(child, label)
00059                 
00060     def _update_tree_view_cb(self, *args, **kwargs):
00061         self._update_pub.publish(str(self._tree_view))
00062         if(self._as is not None):
00063             feedback = airbus_ssm_core.msg.SSMFeedback()
00064             feedback.current_active_states = str(self._tree_view) 
00065             self._as.publish_feedback(feedback)
00066         
00067     def _status_request_cb(self, msg):
00068         self._update_pub.publish(str(self._tree_view))
00069         
00070         


airbus_ssm_core
Author(s): Ludovic Delval
autogenerated on Thu Jun 6 2019 17:59:28