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


phm_hazard_rate_calculation
Author(s):
autogenerated on Thu Aug 13 2020 16:41:45