7 from std_msgs.msg
import Int32, Float64, String
12 system_module = dict(rospy.get_param(
'~System**'))
13 return list(system_module.keys())
18 system_component = dict(rospy.get_param(
'~System**'))
19 return list(system_component.values())
25 read_dict = dict(rospy.get_param(
'~Info**'))
31 read_dict = dict(rospy.get_param(
'~Type**'))
37 read_dict = dict(temp_dict[str(temp_module +
"*")][temp_component])
43 module_type = str(temp_dict[str(temp_module +
"*")][
"type*"])
49 wheel_count = int(rospy.get_param(
'~Wheel_Count'))
57 if temp_type ==
'Serial':
74 result = float(temp_dict[
"ObjectFailureRate"]) * float(temp_dict[
"ObjectCount"])
82 failure_rate_of_parallel_value = 0.0
84 if len(temp_list) > 0:
85 for i
in range(len(temp_list)):
86 failure_rate_of_parallel_value += temp_list[i]
93 return float(failure_rate_of_parallel_value)
97 failure_rate_of_serial_value = 0.0
99 if len(temp_list) > 0:
100 for i
in range(len(temp_list)):
101 failure_rate_of_serial_value += temp_list[i]
103 result = float(failure_rate_of_serial_value)
108 return float(failure_rate_of_serial_value)
114 return float(float(1) - float(value))
118 calculated_parallel_system_reliability = 1.0
120 if len(parallel_list) > 0:
121 for i
in range(len(parallel_list)):
122 calculated_parallel_system_reliability *= parallel_list[i]
124 return float(calculated_parallel_system_reliability)
127 return float(calculated_parallel_system_reliability)
131 calculated_series_system_reliability = 1.0
133 if len(serial_list) > 0:
134 for i
in range(len(serial_list)):
135 calculated_series_system_reliability *= serial_list[i]
137 return float(calculated_series_system_reliability)
140 return float(calculated_series_system_reliability)
147 failure_rate_for_module_list = list()
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
154 component_serial_list = list()
155 component_parallel_list = list()
159 for j
in range(len(component_list[i])):
163 component_type = temp_component_type[
"type"]
164 temp_dict = read_dict
166 if component_type ==
'Serial':
171 component_serial_list.append(temp_serial_value)
172 temp_dict[
"FailureRate"] = temp_serial_value
174 if component_type ==
'Parallel':
179 component_parallel_list.append(temp_parallel_value)
180 temp_dict[
"FailureRate"] = temp_parallel_value
182 temp_dict[
"Type"] = str(component_type)
183 graph_dict[component_list[i][j]] = dict(temp_dict)
188 failure_rate_for_module_list.append(float(failure_rate_for_module_value))
190 temp_system_dict = dict()
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)
200 return failure_rate_for_module_list
204 reliability = math.exp(float(-1) * float(task_usage) * float(module_failure_rate))
206 return float(reliability)
211 if parallel_count == 0:
217 for i
in range(parallel_count):
218 temp = temp + 1/(float(i)+1)
220 return pow(temp, (-1))
224 return round(float(value) * 100, 6)
230 module_usage_during_task_list,
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
240 calculated_system_nominal_reliability = 1.0
241 calculated_series_system_reliability = 1.0
242 calculated_parallel_system_reliability = 1.0
244 reliability_serial_list = list()
245 reliability_parallel_list = list()
249 for i
in range(len(temp_reliability_module)):
253 if temp_reliability_module[i] ==
'Mobility':
255 mobility_reliability = pow(
257 temp_module_usage_during_task_list[i],
258 temp_module_failure_rate[i])),
261 temp_string +=
'\t\tWheel Count = %d \n' % wheel_count
264 nominal_reliability = float(mobility_reliability)
267 nominal_reliability = 1.0
271 temp_module_usage_during_task_list[i],
272 temp_module_failure_rate[i]))
276 temp_string +=
'Modul Name = %s \tModul Value = %d \nFailure Rate = %.10f \tCalculate = %%%f \n' \
278 temp_reliability_module[i],
279 temp_module_usage_during_task_list[i],
280 temp_module_failure_rate[i],
281 percentage_nominal_reliability)
283 temp_string +=
'---------------------------------------\n\n' 285 if module_type ==
'Serial':
287 reliability_serial_list.append(float(nominal_reliability))
289 if module_type ==
'Parallel':
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)
302 if calculated_parallel_system_reliability == 1.0:
303 calculated_parallel_system_reliability = 0
305 calculated_system_nominal_reliability = float(calculated_series_system_reliability) \
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
318 module_name =
"System" 319 graph_dict[str(module_name)] = dict(temp_system_dict)
328 return float(percentage_system_nominal_reliability)
336 module_list = list(graph_dict.keys())
338 graph = pydot.Dot(graph_type=
'digraph')
339 Colors = [
"red",
"orange",
"yellow",
"green",
"#0000ff",
"#976856"]
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")
346 for i
in range(len(module_list)):
347 if str(module_list[i]) == module_name:
351 module_type = str(graph_dict[str(module_list[i])][
"Type"])
353 if module_type ==
'Serial':
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" 363 system[str(i)] = pydot.Node(str(write), style=
"filled", fillcolor=color, shape=
"box")
364 graph.add_node(system[str(i)])
366 for i
in range(len(module_list)):
367 if str(module_list[i]) == module_name:
370 graph.add_edge(pydot.Edge(top_system, system[str(i)]))
372 image_name = module_name +
"_Reliability" 373 write_name =
'/home/hakan/catkin_phm_tools/src/phm_tools/phm_reliability/source/' + str(image_name) +
'.png' 375 graph.write_png(str(write_name))
383 module_list = list(graph_dict.keys())
385 graph = pydot.Dot(graph_type=
'digraph')
386 Colors = [
"red",
"orange",
"yellow",
"green",
"#0000ff",
"#976856"]
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"])
393 top_module = pydot.Node(temp_write, style=
"filled", fillcolor=Colors[4])
395 for i
in range(len(module_list)):
396 if str(module_list[i]) == module_name:
400 module_type = str(graph_dict[str(module_list[i])][
"Type"])
402 if module_type ==
'Serial':
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" 412 system[str(i)] = pydot.Node(str(write), style=
"filled", fillcolor=color, shape=
"house")
413 graph.add_node(system[str(i)])
415 for i
in range(len(module_list)):
416 if str(module_list[i]) == module_name:
420 graph.add_edge(pydot.Edge(top_module, system[str(i)]))
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' 427 graph.write_png(str(write_name))
435 rospy.wait_for_service(
'task_service')
439 task_plan = rospy.ServiceProxy(
'task_service', TaskService)
442 response = task_plan.call(TaskServiceRequest(module))
445 except rospy.ServiceException, e:
446 print "Service call failed: %s" % e
456 for i
in range(len(reliability_module)):
467 return show_value_string
470 return show_value_float
482 value_string_control =
True 493 while not rospy.is_shutdown():
498 module_usage_during_task_list,
500 value_string_control,
503 print (
"%s" % (show_value_string))
504 graph_control =
False 508 if __name__ ==
'__main__':
510 rospy.init_node(
'reliability_node')
511 global reliability_module
512 global component_list
518 except rospy.ROSInterruptException:
def module_usage_during_task()
def reliability_serial_calculation(serial_list)
def get_parameters_info_dict()
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 task_plan_client(module)
def percentage_calculated(value)
def reliability_parallel_calculation(parallel_list)
def get_parameters_type_dict()
def reliability_calculation_function(type_dict, reliability_module, module_usage_during_task_list, module_failure_rate, want_a_string, graph_control)
def reliability_publisher()
def monitoring(want_a_string)
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 reliability_parallel_formula(value)
def create_module_graph(module_name, graph_dict)
def task_plan_client_call(value)
def get_select_parameter_dict(temp_dict, temp_module, temp_component)