phm_reliability_estimation_node.py
Go to the documentation of this file.
1 #!/usr/bin/env python3
2 # -*- coding: utf-8 -*-
3 
4 """
5 
6  PHM Reliability Estimation Node
7 
8 """
9 
10 import rospy
11 from std_msgs.msg import String
12 from phm_msgs.msg import Reliability
13 
14 
16  """
17  Reliability Estimation Node
18 
19  Subscriber:
20  Topic name = /gui_reliability
21  Message type = String
22 
23  Publishler:
24  Topic nane = /phm_reliability
25  Message type = Reliability
26 
27  Rate = 1
28  """
29 
30  def __init__(self):
31  self.phm_gui_control = False
33 
34 
35  def main_func(self):
36  """
37  Reliability Estimation Node Main Function
38  """
39  rospy.Subscriber('/gui_reliability', String, self.phm_gui_reliability_callback_func)
40  publisher_phm_reliability = rospy.Publisher('/phm_reliability', Reliability, queue_size=10)
41 
42  rate = rospy.Rate(1)
43 
44  phm_reliability = Reliability()
45 
46  while not rospy.is_shutdown():
47  if self.phm_gui_control:
48  ros_time = rospy.get_rostime()
49  phm_reliability = self.set_reliability_func(self.phm_gui_reliability, ros_time)
50  publisher_phm_reliability.publish(phm_reliability)
51 
52  rate.sleep()
53 
54 
56  """
57  Callback function of /gui_reliability
58  """
59  self.phm_gui_reliability = dict(eval(phm_msg.data))
60  self.phm_gui_control = True
61 
62  @classmethod
63  def set_reliability_func(cls, reliability_dict, ros_time):
64  """
65  Message function of the /phm_reliability to be published
66  """
67  phm_reliability = Reliability()
68 
69  module_names = list(reliability_dict["System"].keys())
70  module_names.remove("Reliability")
71 
72  system_reliability_keys = list(reliability_dict["System"]["Reliability"].keys())
73  system_reliability_keys.remove("Nominal")
74 
75  phm_reliability.stamp = ros_time
76  phm_reliability.system_value = float(reliability_dict["System"]["Reliability"]["Nominal"])
77 
78  if system_reliability_keys:
79  phm_reliability.system_sensor_based_value = float(reliability_dict["System"]["Reliability"]["Sensor Based"])
80 
81  if module_names:
82  module_values = list()
83  module_sensor_based_values = list()
84  phm_reliability.module_names = list(module_names)
85 
86  for module in module_names:
87  module_reliability_keys = list(reliability_dict["System"][str(module)]["Reliability"].keys())
88  module_reliability_keys.remove("Nominal")
89 
90  current_module_value = float(reliability_dict["System"][str(module)]["Reliability"]["Nominal"])
91  module_values.append(current_module_value)
92 
93  if module_reliability_keys:
94  current_module_sensor_based_value = float(reliability_dict["System"][str(module)]["Reliability"]["Sensor Based"])
95  module_sensor_based_values.append(current_module_sensor_based_value)
96 
97  else:
98  module_sensor_based_values.append(float(0.0))
99 
100  phm_reliability.module_values = module_values
101  phm_reliability.module_sensor_based_values = module_sensor_based_values
102 
103  return phm_reliability
104 
105 
106 if __name__ == '__main__':
107  rospy.init_node('phm_reliability_estimation_node')
108 
109  RELIABILITY_CLASS = ReliabilityEstimationNode()
110  RELIABILITY_CLASS.main_func()


phm_reliability_calculation
Author(s):
autogenerated on Thu Aug 13 2020 16:41:48