python_script_wrapper.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 # Software License Agreement (BSD License)
00003 #
00004 # Copyright (c) 2013, CogniTeam, Inc.
00005 # All rights reserved.
00006 #
00007 # Redistribution and use in source and binary forms, with or without
00008 # modification, are permitted provided that the following conditions
00009 # are met:
00010 #
00011 #  * Redistributions of source code must retain the above copyright
00012 #    notice, this list of conditions and the following disclaimer.
00013 #  * Redistributions in binary form must reproduce the above
00014 #    copyright notice, this list of conditions and the following
00015 #    disclaimer in the documentation and/or other materials provided
00016 #    with the distribution.
00017 #  * Neither the name of Willow Garage, Inc. nor the names of its
00018 #    contributors may be used to endorse or promote products derived
00019 #    from this software without specific prior written permission.
00020 #
00021 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 # POSSIBILITY OF SUCH DAMAGE.
00033 
00034 import robil_monitor_lib
00035 import rospy
00036 from ibus import exception
00037 
00038 class RobilLibProxyVars:
00039         """
00040         Local constant variables
00041         """
00042         @staticmethod
00043         def script_name():
00044                 return "${SCRIPT_NAME}"
00045 
00046 
00047 class RobilLibWrapper:
00048         """
00049         Wrapper of the internal methods
00050         """
00051         def invoke(self, function_name, *args):
00052                 # Construct arguments
00053                 args_tuple = (RobilLibProxyVars.script_name(), function_name)
00054 
00055                 # Convert all arguments to string
00056                 for p in args: args_tuple += (str(p),)
00057 
00058                 # Invoke cpp method
00059                 return robil_monitor_lib.internal_function(args_tuple)
00060 
00061         def topic(self, topic_name):
00062                 # Construct arguments
00063                 args_tuple = (RobilLibProxyVars.script_name(), topic_name)
00064 
00065                 # Invoke cpp method
00066                 return robil_monitor_lib.internal_topic(args_tuple)
00067 
00068 
00069 class ValidatorWrapper:
00070         """
00071         Statement validation wrapper
00072         """
00073         @staticmethod
00074         def internal_validation(validation_state, description):
00075                 # Construct arguments
00076                 args_tuple = (RobilLibProxyVars.script_name(), validation_state, description)
00077 
00078                 # Invoke cpp method to inform about validation result
00079                 robil_monitor_lib.internal_validation(args_tuple)
00080 
00081         @staticmethod
00082         def is_true(bool_expression, description = ""):
00083                 if (bool_expression):
00084                         # Validation succeeded
00085                         ValidatorWrapper.internal_validation(True, description)
00086                 else:
00087                         # Validation failed
00088                         ValidatorWrapper.internal_validation(False, description)
00089 
00090 
00091 
00092 robil_lib       = RobilLibWrapper()
00093 validate        = ValidatorWrapper()
00094 
00095 def topic(topic_name):
00096         return robil_lib.topic(str(topic_name))
00097 
00098 
00099 # ########################
00100 # User code goes below ###
00101 # ########################
00102 
00103 # Simple CPU usage monitor example
00104 
00105 # core1 = robil_lib.topic("/diagnostic/cpu/usage/core1")
00106 # core2 = robil_lib.topic("/diagnostic/cpu/usage/core2")
00107 # core3 = robil_lib.topic("/diagnostic/cpu/usage/core3")
00108 # core4 = robil_lib.topic("/diagnostic/cpu/usage/core4")
00109 
00110 # cpu_threshold = robil_lib.topic("/robot/config/cpu_threshold")
00111 # core_threshold = robil_lib.topic("/robot/config/core_threshold")
00112 
00113 # average = f('average_algorithm', core1, core2, core3, core4)
00114 
00115 # validate.is_true(average < cpu_threshold, "Cpu usage too high!")
00116 # validate.is_true(core1 < core_threshold, "Core1 usage too high")
00117 # validate.is_true(core2 < core_threshold, "Core2 usage too high")
00118 # validate.is_true(core3 < core_threshold, "Core3 usage too high")
00119 # validate.is_true(core4 < core_threshold, "Core4 usage too high")
00120 
00121 


scriptable_monitor
Author(s):
autogenerated on Wed Aug 26 2015 16:21:30