reliability_node.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 # coding=utf-8
3 
4 import rospy
5 import math
6 from phm_task_plan.srv import *
7 from std_msgs.msg import Int32, Float64, String
8 
9 
10 # Yaml Filedaki Moduller
12  system_module = dict(rospy.get_param('~System**'))
13  return list(system_module.keys())
14 
15 
16 # Yaml Filedaki Modullerin Componentleri
18  system_component = dict(rospy.get_param('~System**'))
19  return list(system_component.values())
20 
21 
22 # ------------------------------------------------------------------------------------------
23 
25  read_dict = dict(rospy.get_param('~Info**'))
26 
27  return read_dict
28 
29 
31  read_dict = dict(rospy.get_param('~Type**'))
32 
33  return read_dict
34 
35 
36 def get_select_parameter_dict(temp_dict, temp_module, temp_component):
37  read_dict = dict(temp_dict[str(temp_module + "*")][temp_component])
38 
39  return read_dict
40 
41 
42 def get_select_module_type(temp_dict, temp_module):
43  module_type = str(temp_dict[str(temp_module + "*")]["type*"])
44 
45  return module_type
46 
47 
49  wheel_count = int(rospy.get_param('~Wheel_Count'))
50 
51  return wheel_count
52 
53 
54 # ------------------------------------------------------------------------------------------
55 
56 def object_failure_rate_calculation(temp_dict, temp_type):
57  if temp_type == 'Serial':
59 
60  else:
62 
63 
64 # ------------------------------------------------------------------------------------------
65 
66 # Parallel ise Count u ( 1 + 1/2 + 1/3 + ... 1/ObjectCount) * FailureRate ile çarp
68  result = float(temp_dict["ObjectFailureRate"]) * float(parallel_count_calculate(int(temp_dict["ObjectCount"])))
69 
70  return result
71 
72 
74  result = float(temp_dict["ObjectFailureRate"]) * float(temp_dict["ObjectCount"])
75 
76  return result
77 
78 # ------------------------------------------------------------------------------------------
79 
80 
82  failure_rate_of_parallel_value = 0.0
83 
84  if len(temp_list) > 0:
85  for i in range(len(temp_list)):
86  failure_rate_of_parallel_value += temp_list[i]
87 
88  result = float(failure_rate_of_parallel_value) * float(parallel_count_calculate(len(temp_list)))
89 
90  return float(result)
91 
92  else:
93  return float(failure_rate_of_parallel_value)
94 
95 
97  failure_rate_of_serial_value = 0.0
98 
99  if len(temp_list) > 0:
100  for i in range(len(temp_list)):
101  failure_rate_of_serial_value += temp_list[i]
102 
103  result = float(failure_rate_of_serial_value)
104 
105  return float(result)
106 
107  else:
108  return float(failure_rate_of_serial_value)
109 
110 # ------------------------------------------------------------------------------------------
111 
112 
114  return float(float(1) - float(value))
115 
116 
118  calculated_parallel_system_reliability = 1.0
119 
120  if len(parallel_list) > 0:
121  for i in range(len(parallel_list)):
122  calculated_parallel_system_reliability *= parallel_list[i]
123 
124  return float(calculated_parallel_system_reliability)
125 
126  else:
127  return float(calculated_parallel_system_reliability)
128 
129 
131  calculated_series_system_reliability = 1.0
132 
133  if len(serial_list) > 0:
134  for i in range(len(serial_list)):
135  calculated_series_system_reliability *= serial_list[i]
136 
137  return float(calculated_series_system_reliability)
138 
139  else:
140  return float(calculated_series_system_reliability)
141 
142 # ------------------------------------------------------------------------------------------
143 
144 
145 # λ0 Modülün Hata Oranını Hesaplama
146 def failure_rate_for_modules(reliability_module, component_list, info_dict, type_dict, graph_control):
147  failure_rate_for_module_list = list()
148 
149  for i in range(len(component_list)):
150  failure_rate_of_series_value = 0.0
151  failure_rate_of_parallel_value = 0.0
152  failure_rate_of_parallel_component_count = 0
153 
154  component_serial_list = list()
155  component_parallel_list = list()
156 
157  graph_dict = dict()
158 
159  for j in range(len(component_list[i])):
160  temp_dict = dict()
161  read_dict = get_select_parameter_dict(info_dict, reliability_module[i], component_list[i][j])
162  temp_component_type = get_select_parameter_dict(type_dict, reliability_module[i], component_list[i][j])
163  component_type = temp_component_type["type"]
164  temp_dict = read_dict
165 
166  if component_type == 'Serial': # Component Seri ise Topluyor -> hata oranı ve miktarı çarpıyor.
167  temp_serial_value = float(object_failure_rate_calculation(
168  read_dict,
169  component_type))
170 
171  component_serial_list.append(temp_serial_value)
172  temp_dict["FailureRate"] = temp_serial_value
173 
174  if component_type == 'Parallel': # Component Paralel ise
175  temp_parallel_value = float(object_failure_rate_calculation(
176  read_dict,
177  component_type))
178 
179  component_parallel_list.append(temp_parallel_value)
180  temp_dict["FailureRate"] = temp_parallel_value
181 
182  temp_dict["Type"] = str(component_type)
183  graph_dict[component_list[i][j]] = dict(temp_dict)
184 
185  failure_rate_for_module_value = component_serial_failure_rate_calculation(component_serial_list) \
186  + component_parallel_failure_rate_calculation(component_parallel_list)
187 
188  failure_rate_for_module_list.append(float(failure_rate_for_module_value))
189 
190  temp_system_dict = dict()
191  temp_system_dict["Type"] = get_select_module_type(type_dict, reliability_module[i])
192  temp_system_dict["ObjectCount"] = ''
193  temp_system_dict["ObjectFailureRate"] = ''
194  temp_system_dict["FailureRate"] = failure_rate_for_module_value
195  graph_dict[str(reliability_module[i])] = dict(temp_system_dict)
196 
197  if graph_control:
198  graph_view = create_module_graph(str(reliability_module[i]), graph_dict)
199 
200  return failure_rate_for_module_list
201 
202 
203 def nominal_reliability_calculate(task_usage, module_failure_rate):
204  reliability = math.exp(float(-1) * float(task_usage) * float(module_failure_rate))
205 
206  return float(reliability)
207 
208 
209 # Hazard Rate Parallel Calculate ( 1 + 1/2 + 1/3 + ... + 1/parallel_count )
210 def parallel_count_calculate(parallel_count):
211  if parallel_count == 0:
212  return 1
213 
214  else:
215  temp = 0.0
216 
217  for i in range(parallel_count):
218  temp = temp + 1/(float(i)+1)
219 
220  return pow(temp, (-1))
221 
222 
224  return round(float(value) * 100, 6)
225 
226 
228  type_dict,
229  reliability_module,
230  module_usage_during_task_list,
231  module_failure_rate,
232  want_a_string,
233  graph_control):
234  temp_reliability_module = reliability_module
235  temp_module_usage_during_task_list = module_usage_during_task_list
236  temp_module_failure_rate = module_failure_rate
237 
238  wheel_count = 1
239  temp_string = ''
240  calculated_system_nominal_reliability = 1.0 # System Reliability ( Rsystem )
241  calculated_series_system_reliability = 1.0 # Series Reliability ( Rs = R1 * R2 * ... * Rn )
242  calculated_parallel_system_reliability = 1.0 # Parallel Reliability ( Rp = 1 - Rpi )
243  # Rpi = (1-R1) * (1-R2) * ... * (1-Rn)
244  reliability_serial_list = list()
245  reliability_parallel_list = list()
246 
247  graph_dict = dict()
248 
249  for i in range(len(temp_reliability_module)):
250  temp_dict = dict()
251  module_type = get_select_module_type(type_dict, reliability_module[i])
252 
253  if temp_reliability_module[i] == 'Mobility': # Mobility de Tekerlek sayısına bakıyoruz
254 
255  mobility_reliability = pow(
257  temp_module_usage_during_task_list[i],
258  temp_module_failure_rate[i])),
259  wheel_count)
260 
261  temp_string += '\t\tWheel Count = %d \n' % wheel_count
262 
263  if wheel_count != 0:
264  nominal_reliability = float(mobility_reliability)
265 
266  else:
267  nominal_reliability = 1.0 # Tekerlek Sayisi 0 sa 1 yaparak Çarpımda etkisiz yapıyoruz.
268 
269  else:
270  nominal_reliability = float(nominal_reliability_calculate(
271  temp_module_usage_during_task_list[i],
272  temp_module_failure_rate[i]))
273 
274  # %100 lik reliability sonucu
275  percentage_nominal_reliability = float(percentage_calculated(float(nominal_reliability)))
276  temp_string += 'Modul Name = %s \tModul Value = %d \nFailure Rate = %.10f \tCalculate = %%%f \n' \
277  % (
278  temp_reliability_module[i],
279  temp_module_usage_during_task_list[i],
280  temp_module_failure_rate[i],
281  percentage_nominal_reliability)
282 
283  temp_string += '---------------------------------------\n\n'
284 
285  if module_type == 'Serial':
286  # Series Reliability = Rs = R1 * R2 * ... * Rn
287  reliability_serial_list.append(float(nominal_reliability))
288 
289  if module_type == 'Parallel':
290  # Parallel Reliability = Rpi = (1-R1) * (1-R2) * ... * (1-Rn)
291  reliability_parallel_list.append(reliability_parallel_formula(nominal_reliability))
292 
293  temp_dict["Type"] = str(module_type)
294  temp_dict["ModuleValue"] = temp_module_usage_during_task_list[i]
295  temp_dict["FailureRate"] = temp_module_failure_rate[i]
296  temp_dict["Reliability"] = percentage_nominal_reliability
297  graph_dict[temp_reliability_module[i]] = dict(temp_dict)
298 
299  calculated_series_system_reliability = reliability_serial_calculation(reliability_serial_list)
300  calculated_parallel_system_reliability = reliability_parallel_calculation(reliability_parallel_list)
301 
302  if calculated_parallel_system_reliability == 1.0:
303  calculated_parallel_system_reliability = 0
304 
305  calculated_system_nominal_reliability = float(calculated_series_system_reliability) \
306  * float(reliability_parallel_formula(calculated_parallel_system_reliability))
307  # Rsystem = Rs * (1-Rpi)
308 
309  percentage_system_nominal_reliability = float(percentage_calculated(calculated_system_nominal_reliability))
310  temp_string += '\t\t System Reliability = %%%.10f \n\n' % (float(percentage_system_nominal_reliability))
311  temp_string += '#####################################################################\n\n'
312  temp_system_dict = dict()
313  temp_system_dict["Type"] = ''
314  temp_system_dict["ModuleValue"] = ''
315  temp_system_dict["FailureRate"] = ''
316  temp_system_dict["Reliability"] = percentage_system_nominal_reliability
317 
318  module_name = "System"
319  graph_dict[str(module_name)] = dict(temp_system_dict)
320 
321  if graph_control:
322  graph_view = create_system_graph(module_name, graph_dict)
323 
324  if want_a_string:
325  return temp_string
326 
327  else:
328  return float(percentage_system_nominal_reliability)
329 
330 # ------------------------------------------------------------------------------------------
331 
332 
333 def create_system_graph(module_name, graph_dict):
334  import pydot
335 
336  module_list = list(graph_dict.keys())
337 
338  graph = pydot.Dot(graph_type='digraph')
339  Colors = ["red", "orange", "yellow", "green", "#0000ff", "#976856"]
340 
341  system = dict()
342 
343  temp_write = str(module_name) + "\nReliability = " + str(graph_dict[str(module_name)]["Reliability"])
344  top_system = pydot.Node(temp_write, style="filled", fillcolor=Colors[4], shape="box")
345 
346  for i in range(len(module_list)):
347  if str(module_list[i]) == module_name:
348  continue
349 
350  else:
351  module_type = str(graph_dict[str(module_list[i])]["Type"])
352 
353  if module_type == 'Serial':
354  color = Colors[1]
355 
356  else:
357  color = Colors[3]
358 
359  write = module_list[i] + "\nReliability = " + str(graph_dict[str(module_list[i])]["Reliability"]) \
360  + "\n\nModule Value = " + str(graph_dict[str(module_list[i])]["ModuleValue"]) \
361  + "\nFailure Rate = " + str(graph_dict[str(module_list[i])]["FailureRate"]) + "\n"
362 
363  system[str(i)] = pydot.Node(str(write), style="filled", fillcolor=color, shape="box")
364  graph.add_node(system[str(i)])
365 
366  for i in range(len(module_list)):
367  if str(module_list[i]) == module_name:
368  continue
369  else:
370  graph.add_edge(pydot.Edge(top_system, system[str(i)]))
371 
372  image_name = module_name + "_Reliability"
373  write_name = '/home/hakan/catkin_phm_tools/src/phm_tools/phm_reliability/source/' + str(image_name) + '.png'
374 
375  graph.write_png(str(write_name))
376 
377  return True
378 
379 
380 def create_module_graph(module_name, graph_dict):
381  import pydot
382 
383  module_list = list(graph_dict.keys())
384 
385  graph = pydot.Dot(graph_type='digraph')
386  Colors = ["red", "orange", "yellow", "green", "#0000ff", "#976856"]
387 
388  system = dict()
389 
390  temp_write = str(module_name) + "\nFailure Rate = " + str(graph_dict[str(module_name)]["FailureRate"]) \
391  + "\n\nType = " + str(graph_dict[str(module_name)]["Type"])
392 
393  top_module = pydot.Node(temp_write, style="filled", fillcolor=Colors[4])
394 
395  for i in range(len(module_list)):
396  if str(module_list[i]) == module_name:
397  continue
398 
399  else:
400  module_type = str(graph_dict[str(module_list[i])]["Type"])
401 
402  if module_type == 'Serial':
403  color = Colors[1]
404 
405  else:
406  color = Colors[3]
407 
408  write = module_list[i] + "\nFailure Rate = " + str(graph_dict[str(module_list[i])]["FailureRate"]) \
409  + "\n\nObject Count = " + str(graph_dict[str(module_list[i])]["ObjectCount"]) \
410  + "\nObject Failure Rate = " + str(graph_dict[str(module_list[i])]["ObjectFailureRate"]) + "\n"
411 
412  system[str(i)] = pydot.Node(str(write), style="filled", fillcolor=color, shape="house")
413  graph.add_node(system[str(i)])
414 
415  for i in range(len(module_list)):
416  if str(module_list[i]) == module_name:
417  continue
418 
419  else:
420  graph.add_edge(pydot.Edge(top_module, system[str(i)]))
421 
422  image_name = str(module_name)
423  image_name = image_name.replace(" ", "_")
424  write_name = '/home/hakan/catkin_phm_tools/src/phm_tools/phm_reliability/source/module/' \
425  + str(image_name) + '.png'
426 
427  graph.write_png(str(write_name))
428 
429  return True
430 
431 # ------------------------------------------------------------------------------------------
432 
433 
434 def task_plan_client(module):
435  rospy.wait_for_service('task_service')
436 
437  try:
438  # create a handle to the task_plan service
439  task_plan = rospy.ServiceProxy('task_service', TaskService)
440 
441  # formal style
442  response = task_plan.call(TaskServiceRequest(module))
443 
444  return response.task
445  except rospy.ServiceException, e:
446  print "Service call failed: %s" % e
447 
448 
450  return task_plan_client(value)
451 
452 
454  temp_list = list()
455 
456  for i in range(len(reliability_module)):
457  temp_list.append(task_plan_client_call(reliability_module[i]))
458 
459  return temp_list
460 
461 # ------------------------------------------------------------------------------------------
462 
463 
464 def monitoring(want_a_string):
465 
466  if want_a_string:
467  return show_value_string
468 
469  else:
470  return show_value_float
471 
472 # ------------------------------------------------------------------------------------------
473 
474 
476  # rospy.init_node('reliability_node')
477  # pub=rospy.Publisher('Deneme_Background', Float64, queue_size=10)
478  rate = rospy.Rate(2)
479 
480  # kontrol = 0
481  graph_control = True
482  value_string_control = True
483  info_dict = get_parameters_info_dict()
484  type_dict = get_parameters_type_dict()
485  # wheel_count = get_wheel_count()
486 
487  module_failure_rate = failure_rate_for_modules(
488  reliability_module,
489  component_list,
490  info_dict,
491  type_dict,
492  graph_control)
493  while not rospy.is_shutdown():
494 
495  show_value_string = reliability_calculation_function(
496  type_dict,
497  reliability_module,
498  module_usage_during_task_list,
499  module_failure_rate,
500  value_string_control,
501  graph_control)
502 
503  print ("%s" % (show_value_string))
504  graph_control = False
505 
506  rate.sleep()
507 
508 if __name__ == '__main__':
509  try:
510  rospy.init_node('reliability_node')
511  global reliability_module
512  global component_list
513  reliability_module = module_array()
514  component_list = component_array()
515 
516  module_usage_during_task_list = module_usage_during_task()
518  except rospy.ROSInterruptException:
519  pass
def reliability_serial_calculation(serial_list)
def object_serial_failure_rate_calculation(temp_dict)
def failure_rate_for_modules(reliability_module, component_list, info_dict, type_dict, graph_control)
def component_serial_failure_rate_calculation(temp_list)
def get_select_module_type(temp_dict, temp_module)
def create_system_graph(module_name, graph_dict)
def object_parallel_failure_rate_calculation(temp_dict)
def component_parallel_failure_rate_calculation(temp_list)
def reliability_parallel_calculation(parallel_list)
def reliability_calculation_function(type_dict, reliability_module, module_usage_during_task_list, module_failure_rate, want_a_string, graph_control)
def parallel_count_calculate(parallel_count)
def object_failure_rate_calculation(temp_dict, temp_type)
def nominal_reliability_calculate(task_usage, module_failure_rate)
def create_module_graph(module_name, graph_dict)
def get_select_parameter_dict(temp_dict, temp_module, temp_component)


phm_reliability
Author(s):
autogenerated on Mon Jun 10 2019 14:13:33