diff --git a/.gitignore b/.gitignore index 89c05dd..b25b9b9 100644 --- a/.gitignore +++ b/.gitignore @@ -2,6 +2,7 @@ test.py .idea/ .venv/ assets/logs/ +assets/files/examples/ package/ code/common/__pycache__/ code/data_process/__pycache__/ diff --git a/assets/files/projects/NB4h_R580_3G.zip b/assets/files/projects/NB4h_R580_3G.zip index ef5993e..3ef67a6 100644 Binary files a/assets/files/projects/NB4h_R580_3G.zip and b/assets/files/projects/NB4h_R580_3G.zip differ diff --git a/assets/files/projects/configs.xlsx b/assets/files/projects/configs.xlsx index d7eb8d4..82d6efa 100644 Binary files a/assets/files/projects/configs.xlsx and b/assets/files/projects/configs.xlsx differ diff --git a/assets/files/protocols/collision.get_params.json b/assets/files/protocols/collision.get_params.json new file mode 100644 index 0000000..62b0a45 --- /dev/null +++ b/assets/files/protocols/collision.get_params.json @@ -0,0 +1,5 @@ +{ + "id": "xxxxxxxxxxx", + "module": "safety", + "command": "collision.get_params" +} \ No newline at end of file diff --git a/assets/files/protocols/collision.set_params.json b/assets/files/protocols/collision.set_params.json new file mode 100644 index 0000000..813f7ca --- /dev/null +++ b/assets/files/protocols/collision.set_params.json @@ -0,0 +1,6 @@ +{ + "id": "xxxxxxxxxxx", + "module": "safety", + "command": "collision.set_params", + "data": null +} \ No newline at end of file diff --git a/assets/files/protocols/collision.set_state.json b/assets/files/protocols/collision.set_state.json new file mode 100644 index 0000000..04bfbb5 --- /dev/null +++ b/assets/files/protocols/collision.set_state.json @@ -0,0 +1,7 @@ +{ + "module": "safety", + "command": "collision.set_state", + "data": { + "collision_state": false + } +} \ No newline at end of file diff --git a/assets/files/protocols/controller.get_params.json b/assets/files/protocols/controller.get_params.json index f549e6d..92dac53 100644 --- a/assets/files/protocols/controller.get_params.json +++ b/assets/files/protocols/controller.get_params.json @@ -1,5 +1,5 @@ -{ - "id": "xxxxxxxxxxx", - "module": "system", - "command": "controller.get_params" +{ + "id":"xxxxxxxxxxx", + "module":"system", + "command":"controller.get_params" } \ No newline at end of file diff --git a/assets/files/protocols/controller.reboot.json b/assets/files/protocols/controller.reboot.json new file mode 100644 index 0000000..a0ef6da --- /dev/null +++ b/assets/files/protocols/controller.reboot.json @@ -0,0 +1,8 @@ +{ + "id": "xxxxxxxxxxx", + "module": "system", + "command": "controller.reboot", + "data": { + "arg": 6 + } +} \ No newline at end of file diff --git a/assets/files/protocols/controller.set_params.json b/assets/files/protocols/controller.set_params.json new file mode 100644 index 0000000..3759298 --- /dev/null +++ b/assets/files/protocols/controller.set_params.json @@ -0,0 +1,8 @@ +{ + "id": "xxxxxxxxxxx", + "module": "system", + "command": "controller.set_params", + "data": { + "time": "2020-02-28 15:28:30" + } +} \ No newline at end of file diff --git a/assets/files/protocols/drag.get_params.json b/assets/files/protocols/drag.get_params.json new file mode 100644 index 0000000..9c56d28 --- /dev/null +++ b/assets/files/protocols/drag.get_params.json @@ -0,0 +1,5 @@ +{ + "id": "xxxxxxxxxxx", + "module": "dynamic", + "command": "drag.get_params" +} \ No newline at end of file diff --git a/assets/files/protocols/drag.set_params.json b/assets/files/protocols/drag.set_params.json new file mode 100644 index 0000000..52b0b6f --- /dev/null +++ b/assets/files/protocols/drag.set_params.json @@ -0,0 +1,10 @@ +{ + "id": "xxxxxxxxxxx", + "module": "dynamic", + "command": "drag.set_params", + "data": { + "enable": true, + "space": 0, + "type": 0 + } +} \ No newline at end of file diff --git a/assets/files/protocols/fieldbus_device.get_params.json b/assets/files/protocols/fieldbus_device.get_params.json new file mode 100644 index 0000000..6eca806 --- /dev/null +++ b/assets/files/protocols/fieldbus_device.get_params.json @@ -0,0 +1,5 @@ +{ + "id": "xxxxxxxxxxx", + "module": "fieldbus", + "command": "fieldbus_device.get_params" +} \ No newline at end of file diff --git a/assets/files/protocols/fieldbus_device.load_cfg.json b/assets/files/protocols/fieldbus_device.load_cfg.json new file mode 100644 index 0000000..79e1731 --- /dev/null +++ b/assets/files/protocols/fieldbus_device.load_cfg.json @@ -0,0 +1,8 @@ +{ + "id": "xxxxxxxxxxx", + "module": "fieldbus", + "command": "fieldbus_device.load_cfg", + "data": { + "file_name": "fieldbus_device.json" + } +} \ No newline at end of file diff --git a/assets/files/protocols/fieldbus_device.set_params.json b/assets/files/protocols/fieldbus_device.set_params.json new file mode 100644 index 0000000..d6828f6 --- /dev/null +++ b/assets/files/protocols/fieldbus_device.set_params.json @@ -0,0 +1,9 @@ +{ + "id": "xxxxxxxxxxx", + "module": "fieldbus", + "command": "fieldbus_device.set_params", + "data": { + "device_name": "modbus_1", + "enable": true + } +} \ No newline at end of file diff --git a/assets/files/protocols/io_device.load_cfg.json b/assets/files/protocols/io_device.load_cfg.json new file mode 100644 index 0000000..790f75c --- /dev/null +++ b/assets/files/protocols/io_device.load_cfg.json @@ -0,0 +1,5 @@ +{ + "id": "xxxxxxxxxxx", + "module": "io", + "command": "io_device.load_cfg" +} \ No newline at end of file diff --git a/assets/files/protocols/jog.get_params.json b/assets/files/protocols/jog.get_params.json new file mode 100644 index 0000000..db98a71 --- /dev/null +++ b/assets/files/protocols/jog.get_params.json @@ -0,0 +1,5 @@ +{ + "id": "xxxxxxxxxxx", + "module": "motion", + "command": "jog.get_params" +} \ No newline at end of file diff --git a/assets/files/protocols/jog.set_params.json b/assets/files/protocols/jog.set_params.json new file mode 100644 index 0000000..6c89d14 --- /dev/null +++ b/assets/files/protocols/jog.set_params.json @@ -0,0 +1,10 @@ +{ + "id": "xxxxxxxxxxx", + "module": "motion", + "command": "jog.set_params", + "data": { + "step": 1000, + "override": 0.2, + "space": 5 + } +} \ No newline at end of file diff --git a/assets/files/protocols/jog.start.json b/assets/files/protocols/jog.start.json new file mode 100644 index 0000000..afe54cc --- /dev/null +++ b/assets/files/protocols/jog.start.json @@ -0,0 +1,10 @@ +{ + "id": "xxxxxxxxxxx", + "module": "motion", + "command": "jog.start", + "data": { + "index": 0, + "direction": true, + "is_ext": false + } +} \ No newline at end of file diff --git a/assets/files/protocols/log_code.data.code_list.json b/assets/files/protocols/log_code.data.code_list.json new file mode 100644 index 0000000..c6f1ee2 --- /dev/null +++ b/assets/files/protocols/log_code.data.code_list.json @@ -0,0 +1,8 @@ +{ + "id": "log_code.data.code_list", + "s": { + "log_code.data": { + "code_list": [] + } + } +} \ No newline at end of file diff --git a/assets/files/protocols/log_code.data.json b/assets/files/protocols/log_code.data.json new file mode 100644 index 0000000..021b678 --- /dev/null +++ b/assets/files/protocols/log_code.data.json @@ -0,0 +1,5 @@ +{ + "g": { + "log_code.data": "null" + } +} \ No newline at end of file diff --git a/assets/files/protocols/modbus.get_params.json b/assets/files/protocols/modbus.get_params.json new file mode 100644 index 0000000..8bdde30 --- /dev/null +++ b/assets/files/protocols/modbus.get_params.json @@ -0,0 +1,5 @@ +{ + "id": "xxxxxxxxxxx", + "module": "fieldbus", + "command": "modbus.get_params" +} \ No newline at end of file diff --git a/assets/files/protocols/modbus.get_values.json b/assets/files/protocols/modbus.get_values.json new file mode 100644 index 0000000..d356362 --- /dev/null +++ b/assets/files/protocols/modbus.get_values.json @@ -0,0 +1,8 @@ +{ + "id": "xxxxxxxxxxx", + "module": "fieldbus", + "command": "modbus.get_values", + "data": { + "mode": "all" + } +} \ No newline at end of file diff --git a/assets/files/protocols/modbus.load_cfg.json b/assets/files/protocols/modbus.load_cfg.json new file mode 100644 index 0000000..95d5e69 --- /dev/null +++ b/assets/files/protocols/modbus.load_cfg.json @@ -0,0 +1,8 @@ +{ + "id": "xxxxxxxxxxx", + "module": "fieldbus", + "command": "modbus.load_cfg", + "data": { + "file" : "registers.json" + } +} \ No newline at end of file diff --git a/assets/files/protocols/modbus.set_params.json b/assets/files/protocols/modbus.set_params.json new file mode 100644 index 0000000..46a651e --- /dev/null +++ b/assets/files/protocols/modbus.set_params.json @@ -0,0 +1,12 @@ +{ + "id": "xxxxxxxxxxx", + "module": "fieldbus", + "command": "modbus.set_params", + "data": { + "enable_slave": true, + "ip": "192.168.0.160", + "port": 502, + "slave_id": 0, + "enable_master": false + } +} \ No newline at end of file diff --git a/assets/files/protocols/move.get_joint_pos.json b/assets/files/protocols/move.get_joint_pos.json new file mode 100644 index 0000000..9754405 --- /dev/null +++ b/assets/files/protocols/move.get_joint_pos.json @@ -0,0 +1,5 @@ +{ + "id": "xxxxxxxxxxx", + "module": "motion", + "command": "move.get_joint_pos" +} \ No newline at end of file diff --git a/assets/files/protocols/move.get_monitor_cfg.json b/assets/files/protocols/move.get_monitor_cfg.json new file mode 100644 index 0000000..75fb033 --- /dev/null +++ b/assets/files/protocols/move.get_monitor_cfg.json @@ -0,0 +1,5 @@ +{ + "id": "xxxxxxxxxxx", + "module": "motion", + "command": "move.get_monitor_cfg" +} \ No newline at end of file diff --git a/assets/files/protocols/move.get_params.json b/assets/files/protocols/move.get_params.json new file mode 100644 index 0000000..bfe06e2 --- /dev/null +++ b/assets/files/protocols/move.get_params.json @@ -0,0 +1,5 @@ +{ + "id": "xxxxxxxxxxx", + "module": "motion", + "command": "move.get_params" +} \ No newline at end of file diff --git a/assets/files/protocols/move.get_pos.json b/assets/files/protocols/move.get_pos.json new file mode 100644 index 0000000..9124631 --- /dev/null +++ b/assets/files/protocols/move.get_pos.json @@ -0,0 +1,5 @@ +{ + "id": "xxxxxxxxxxx", + "module": "motion", + "command": "move.get_pos" +} \ No newline at end of file diff --git a/assets/files/protocols/move.get_quickstop_distance.json b/assets/files/protocols/move.get_quickstop_distance.json new file mode 100644 index 0000000..ac5f0b2 --- /dev/null +++ b/assets/files/protocols/move.get_quickstop_distance.json @@ -0,0 +1,5 @@ +{ + "id": "xxxxxxxxxxx", + "module": "motion", + "command": "move.get_quickstop_distance" +} \ No newline at end of file diff --git a/assets/files/protocols/move.get_quickturn_pos.json b/assets/files/protocols/move.get_quickturn_pos.json new file mode 100644 index 0000000..74ecae0 --- /dev/null +++ b/assets/files/protocols/move.get_quickturn_pos.json @@ -0,0 +1,5 @@ +{ + "id" : "xxxxxxxxx", + "module": "motion", + "command": "move.get_quickturn_pos" +} \ No newline at end of file diff --git a/assets/files/protocols/move.quick_turn.json b/assets/files/protocols/move.quick_turn.json new file mode 100644 index 0000000..3a72afc --- /dev/null +++ b/assets/files/protocols/move.quick_turn.json @@ -0,0 +1,8 @@ +{ + "id": "xxxxxxxxxxx", + "module": "motion", + "command": "move.quick_turn", + "data": { + "name":"home" + } +} \ No newline at end of file diff --git a/assets/files/protocols/move.set_monitor_cfg.json b/assets/files/protocols/move.set_monitor_cfg.json new file mode 100644 index 0000000..68c3f35 --- /dev/null +++ b/assets/files/protocols/move.set_monitor_cfg.json @@ -0,0 +1,8 @@ +{ + "id": "xxxxxxxxxxx", + "module": "motion", + "command": "move.set_monitor_cfg", + "data": { + "ref_coordinate": 1 + } +} \ No newline at end of file diff --git a/assets/files/protocols/move.set_params.json b/assets/files/protocols/move.set_params.json new file mode 100644 index 0000000..8788a6c --- /dev/null +++ b/assets/files/protocols/move.set_params.json @@ -0,0 +1,17 @@ +{ + "id": "xxxxxxxxxxx", + "module": "motion", + "command": "move.set_params", + "data": { + "MOTION": { + "JOINT_MAX_SPEED": [1.0,0.0,0.0,0.0,0.0,0.0], + "JOINT_MAX_ACC": [1.0,0.0,0.0,0.0,0.0,0.0], + "JOINT_MAX_JERK": [1.0,0.0,0.0], + "TCP_MAX_SPEED": 500, + "DEFAULT_ACC_PARAMS": [0.3,1.0], + "VEL_SMOOTH_FACTOR": 3.33, + "ACC_RAMPTIME_JOG": 0.01 + } + } + +} \ No newline at end of file diff --git a/assets/files/protocols/move.set_quickstop_distance.json b/assets/files/protocols/move.set_quickstop_distance.json new file mode 100644 index 0000000..000d5f5 --- /dev/null +++ b/assets/files/protocols/move.set_quickstop_distance.json @@ -0,0 +1,8 @@ +{ + "id": "xxxxxxxxxxx", + "module": "motion", + "command": "move.set_quickstop_distance", + "data":{ + "distance": 2 + } +} \ No newline at end of file diff --git a/assets/files/protocols/move.set_quickturn_pos.json b/assets/files/protocols/move.set_quickturn_pos.json new file mode 100644 index 0000000..164e442 --- /dev/null +++ b/assets/files/protocols/move.set_quickturn_pos.json @@ -0,0 +1,15 @@ +{ + "id" : "xxxxxxxxx", + "module": "motion", + "command": "move.set_quickturn_pos", + "data": { + "enable_home": false, + "enable_drag": false, + "enable_transport": false, + "joint_home": [0.0,0.0,0.0,0.0,0.0,0.0,0.0], + "joint_drag": [0.0,0.0,0.0,0.0,0.0,0.0,0.0], + "joint_transport": [0.0,0.0,0.0,0.0,0.0,0.0,0.0], + "end_posture": 0, + "home_error_range":[0.0,0.0,0.0,0.0,0.0,0.0,0.0] + } +} \ No newline at end of file diff --git a/assets/files/protocols/move.stop.json b/assets/files/protocols/move.stop.json new file mode 100644 index 0000000..17648f0 --- /dev/null +++ b/assets/files/protocols/move.stop.json @@ -0,0 +1,8 @@ +{ + "id": "xxxxxxxxxxx", + "module": "motion", + "command": "move.stop", + "data":{ + "stoptype": 0 + } +} \ No newline at end of file diff --git a/assets/files/protocols/safety.safety_area.overall_enable.json b/assets/files/protocols/safety.safety_area.overall_enable.json new file mode 100644 index 0000000..517e64b --- /dev/null +++ b/assets/files/protocols/safety.safety_area.overall_enable.json @@ -0,0 +1,7 @@ +{ + "c": { + "safety.safety_area.overall_enable": { + "enable": true + } + } +} \ No newline at end of file diff --git a/assets/files/protocols/safety.safety_area.safety_area_enable.json b/assets/files/protocols/safety.safety_area.safety_area_enable.json new file mode 100644 index 0000000..505fe50 --- /dev/null +++ b/assets/files/protocols/safety.safety_area.safety_area_enable.json @@ -0,0 +1,8 @@ +{ + "c": { + "safety.safety_area.safety_area_enable": { + "id": 0, + "enable": true + } + } +} \ No newline at end of file diff --git a/assets/files/protocols/safety.safety_area.set_param.json b/assets/files/protocols/safety.safety_area.set_param.json new file mode 100644 index 0000000..28b65da --- /dev/null +++ b/assets/files/protocols/safety.safety_area.set_param.json @@ -0,0 +1,5 @@ +{ + "c": { + "safety.safety_area.set_param": null + } +} \ No newline at end of file diff --git a/assets/files/protocols/safety.safety_area.signal_enable.json b/assets/files/protocols/safety.safety_area.signal_enable.json new file mode 100644 index 0000000..8a1fbac --- /dev/null +++ b/assets/files/protocols/safety.safety_area.signal_enable.json @@ -0,0 +1,7 @@ +{ + "c": { + "safety.safety_area.signal_enable": { + "signal": true + } + } +} \ No newline at end of file diff --git a/assets/files/protocols/safety_area_data.json b/assets/files/protocols/safety_area_data.json new file mode 100644 index 0000000..e9b982a --- /dev/null +++ b/assets/files/protocols/safety_area_data.json @@ -0,0 +1,5 @@ +{ + "g": { + "safety_area_data": null + } +} \ No newline at end of file diff --git a/assets/files/protocols/servo.clear_alarm.json b/assets/files/protocols/servo.clear_alarm.json new file mode 100644 index 0000000..bc3b7f8 --- /dev/null +++ b/assets/files/protocols/servo.clear_alarm.json @@ -0,0 +1,5 @@ +{ + "id": "xxxxxxxxxxx", + "module": "robot", + "command": "servo.clear_alarm" +} \ No newline at end of file diff --git a/assets/files/protocols/socket.get_params.json b/assets/files/protocols/socket.get_params.json new file mode 100644 index 0000000..2971e6a --- /dev/null +++ b/assets/files/protocols/socket.get_params.json @@ -0,0 +1,5 @@ +{ + "id": "xxxxxxxxxxx", + "module": "network", + "command": "socket.get_params" +} \ No newline at end of file diff --git a/assets/files/protocols/socket.set_params.json b/assets/files/protocols/socket.set_params.json new file mode 100644 index 0000000..9635cae --- /dev/null +++ b/assets/files/protocols/socket.set_params.json @@ -0,0 +1,17 @@ +{ + "id": "xxxxxxxxxxx", + "module": "network", + "command": "socket.set_params", + "data": { + "enable": true, + "ip": "", + "name": "c1", + "port": "8080", + "suffix": "\r", + "type": 1, + "reconnect_flag": false, + "auto_connect": true, + "disconnection_triggering_behavior": 0, + "disconnection_detection_time": 10 + } +} \ No newline at end of file diff --git a/assets/files/protocols/soft_limit.get_params.json b/assets/files/protocols/soft_limit.get_params.json new file mode 100644 index 0000000..6f1f222 --- /dev/null +++ b/assets/files/protocols/soft_limit.get_params.json @@ -0,0 +1,5 @@ +{ + "id": "xxxxxxxxxxx", + "module": "safety", + "command": "soft_limit.get_params" +} \ No newline at end of file diff --git a/assets/files/protocols/soft_limit.set_params.json b/assets/files/protocols/soft_limit.set_params.json new file mode 100644 index 0000000..a0a3844 --- /dev/null +++ b/assets/files/protocols/soft_limit.set_params.json @@ -0,0 +1,12 @@ +{ + "id": "xxxxxxxxxxx", + "module": "safety", + "command": "soft_limit.set_params", + "data": { + "enable": true, + "upper": [0,0,0,0,0,0,0], + "lower": [0,0,0,0,0,0,0], + "reduced_upper": [0,0,0,0,0,0,0], + "reduced_lower": [0,0,0,0,0,0,0] + } +} \ No newline at end of file diff --git a/assets/files/protocols/system_io.query_configuration.json b/assets/files/protocols/system_io.query_configuration.json new file mode 100644 index 0000000..27d16bd --- /dev/null +++ b/assets/files/protocols/system_io.query_configuration.json @@ -0,0 +1,5 @@ +{ + "id": "xxxxxxxxxxx", + "module": "io", + "command": "system_io.query_configuration" +} \ No newline at end of file diff --git a/assets/files/protocols/system_io.query_event_cfg.json b/assets/files/protocols/system_io.query_event_cfg.json new file mode 100644 index 0000000..5af3217 --- /dev/null +++ b/assets/files/protocols/system_io.query_event_cfg.json @@ -0,0 +1,5 @@ +{ + "id": "xxxxxxxxxxx", + "module": "io", + "command": "system_io.query_event_cfg" +} \ No newline at end of file diff --git a/assets/files/protocols/system_io.update_configuration.json b/assets/files/protocols/system_io.update_configuration.json new file mode 100644 index 0000000..aaeb41f --- /dev/null +++ b/assets/files/protocols/system_io.update_configuration.json @@ -0,0 +1,9 @@ +{ + "id": "xxxxxxxxxxx", + "module": "io", + "command": "system_io.update_configuration", + "data": { + "input_system_io": {}, + "output_system_io": {} + } +} \ No newline at end of file diff --git a/code/aio.py b/code/aio.py index 3d9591c..f37a4b7 100644 --- a/code/aio.py +++ b/code/aio.py @@ -15,7 +15,7 @@ from datetime import datetime import os from common import clibs, openapi from data_process import current, brake, iso, wavelogger -from automatic_test import do_current +from automatic_test import do_current, do_brake import threading import re @@ -298,7 +298,7 @@ class App: def __is_running(operation): if clibs.running: messagebox.showerror(title="处理中", message=f"有程序正在运行,需等待结束后,在执行{operation}操作!") - return + return "running" def __program_start(self): def get_data_dp(): @@ -323,7 +323,8 @@ class App: return data def init_op(): - self.__is_running("开始") + if self.__is_running("开始") == "running": + return self.text_output.delete("1.0", ctk.END) self.tabview_bottom.set("输出") clibs.tl_prg = self.__toplevel_progress @@ -339,27 +340,21 @@ class App: def exec_function(): init_op() if self.tabview_top.get() == "数据处理": - if not clibs.running: - clibs.running = True - clibs.data_dp = get_data_dp() - try: - eval(clibs.data_dp["_main"] + ".main()") - finally: - clibs.running = False - clibs.stop = False - else: - messagebox.showinfo(title="进行中...", message="当前有程序正在运行!") + clibs.running = True + clibs.data_dp = get_data_dp() + try: + eval(clibs.data_dp["_main"] + ".main()") + finally: + clibs.running = False + clibs.stop = False elif self.tabview_top.get() == "自动测试": - if not clibs.running: - clibs.running = True - clibs.data_at = get_data_at() - try: - eval("do_" + clibs.data_at["_main"] + ".main()") - finally: - clibs.running = False - clibs.stop = False - else: - messagebox.showinfo(title="进行中...", message="当前有程序正在运行!") + clibs.running = True + clibs.data_at = get_data_at() + try: + eval("do_" + clibs.data_at["_main"] + ".main()") + finally: + clibs.running = False + clibs.stop = False exec_function() @@ -371,7 +366,8 @@ class App: self.entry_path_atv.set("数据文件夹路径") self.entry_path_atv.set("数据文件夹路径") - self.__is_running("重置") + if self.__is_running("重置") == "running": + return if clibs.db_state == "readwrite": res = messagebox.askyesno(title="状态重置", message="这将清空本次所有的输出以及日志记录,且不可恢复,请确认!", default=messagebox.NO, icon=messagebox.WARNING) @@ -522,7 +518,8 @@ class App: get_next_page() def __load_log_db(self): - self.__is_running("加载") + if self.__is_running("加载") == "running": + return db_file = filedialog.askopenfilename(title="加载数据库文件", defaultextension=".db", initialdir=f"{clibs.PREFIX}/logs") if not db_file: return @@ -979,10 +976,9 @@ class App: clibs.c_md = openapi.ModbusRequest(clibs.ip_addr, clibs.modbus_port) clibs.c_hr = openapi.HmiRequest(clibs.ip_addr, clibs.socket_port, clibs.xService_port) clibs.c_pd = openapi.PreDos(clibs.ip_addr, clibs.ssh_port, clibs.username, clibs.password) - # clibs.c_md.read_scenario_time() + + # clibs.c_md.write_speed_max(123.456) # clibs.c_hr.execution('state.set_tp_mode', tp_mode='without') - # clibs.c_hr.execution("diagnosis.open", open=False, display_open=False, overrun=True, turn_area=True, delay_motion=False) - # clibs.c_hr.execution("diagnosis.set_params", display_pdo_params=[], frequency=50, version="1.4.1") self.btn_conn.configure(state="normal", fg_color="#2E8B57") except Exception: self.btn_conn.configure(state="normal", fg_color="#979DA2") diff --git a/code/automatic_test/do_brake.py b/code/automatic_test/do_brake.py index 6961380..6cace4f 100644 --- a/code/automatic_test/do_brake.py +++ b/code/automatic_test/do_brake.py @@ -4,33 +4,33 @@ import paramiko import openpyxl import pandas import json -from commons import clibs +from common import clibs, openapi def initialization(path, sub, data_dirs, data_files, hr, w2t): def check_files(): - if len(data_dirs) != 0 or len(data_files) != 6: - w2t("初始路径下不允许有文件夹,且初始路径下只能存在如下五个文件,确认后重新运行!", "red") - w2t("1. configs.xlsx\n2. reach33/reach66/reach100_xxxx.xlsx\n3. xxxx.zip\n", "red", "InitFileError") + msg = "初始路径下不允许有文件夹,且初始路径下只能存在如下五个文件,确认后重新运行!\n" + msg += "1. configs.xlsx\n2. reach33/reach66/reach100_xxxx.xlsx\n3. xxxx.zip\n" + if len(data_dirs) != 0 or len(data_files) != 5: + w2t(msg, "red", "InitFileError") - config_file, reach33, reach66, reach100, prj_file, result_dirs = None, None, None, None, None, [] + config_file, reach33_file, reach66_file, reach100_file, prj_file, result_dirs = None, None, None, None, None, [] for data_file in data_files: filename = data_file.split("/")[-1] if filename == "configs.xlsx": config_file = data_file elif filename.startswith("reach33_") and filename.endswith(".xlsx"): - reach33 = data_file + reach33_file = data_file elif filename.startswith("reach66_") and filename.endswith(".xlsx"): - reach66 = data_file + reach66_file = data_file elif filename.startswith("reach100_") and filename.endswith(".xlsx"): - reach100 = data_file + reach100_file = data_file elif filename.endswith(".zip"): prj_file = data_file else: - w2t("初始路径下不允许有文件夹,且初始路径下只能存在如下五个文件,确认后重新运行!", "red") - w2t("1. configs.xlsx\n2. reach33/reach66/reach100_xxxx.xlsx\n3. xxxx.zip\n", "red", "InitFileError") + w2t(msg, "red", "InitFileError") - if config_file and reach33 and reach66 and reach100 and prj_file: + if config_file and reach33_file and reach66_file and reach100_file and prj_file: os.mkdir(f"{path}/j1") os.mkdir(f"{path}/j2") os.mkdir(f"{path}/j3") @@ -46,10 +46,9 @@ def initialization(path, sub, data_dirs, data_files, hr, w2t): os.mkdir(f"{path}/j3/{dir_name}") w2t("数据目录合规性检查结束,未发现问题......\n", "blue") - return config_file, reach33, reach66, reach100, prj_file, result_dirs + return config_file, prj_file, result_dirs else: - w2t("初始路径下不允许有文件夹,且初始路径下只能存在如下五个文件,确认后重新运行!", "red") - w2t("1. configs.xlsx\n2. reach33/reach66/reach100_xxxx.xlsx\n3. xxxx.zip\n", "red", "InitFileError") + w2t(msg, "red", "InitFileError") def get_configs(): robot_type = None @@ -76,40 +75,45 @@ def initialization(path, sub, data_dirs, data_files, hr, w2t): clibs.insert_logdb("INFO", "do_brake", f"get_configs: 各关节角速度 {avs}") return avs - _config_file, _reach33, _reach66, _reach100, _prj_file, _result_dirs = check_files() + clibs.c_hr.set_socket_params(True, str(clibs.external_port), "\r", 1) + clibs.c_ec = openapi.ExternalCommunication(clibs.ip_addr, clibs.external_port) + + _config_file, _prj_file, _result_dirs = check_files() _avs = get_configs() - return _config_file, _reach33, _reach66, _reach100, _prj_file, _result_dirs, _avs + return _config_file, _prj_file, _result_dirs, _avs @clibs.db_lock -def gen_result_file(path, axis, reach, load, speed, rounds): +def gen_result_file(path, axis, t_end, reach, load, speed, rounds): d_vel, d_trq, d_stop = [], [], [] - len_records = 12 * 1000 // 50 - clibs.cursor.execute(f"select content from logs where content like 'diagnosis.result' limit {len_records}") + start_time = time.strftime("%Y-%m-%d %H:%M:%S", time.localtime(t_end-12)) + end_time = time.strftime("%Y-%m-%d %H:%M:%S", time.localtime(t_end)) + clibs.cursor.execute(f"select content from logs where time between '{start_time}' and '{end_time}' and content like '%diagnosis.result%' order by id asc") records = clibs.cursor.fetchall() for record in records: # 保留最后12s的数据 - data = eval(record)["data"] + data = eval(record[0])["data"] for item in data: + d_item = reversed(item["value"]) if item.get("channel", None) == axis-1 and item.get("name", None) == "hw_joint_vel_feedback": - d_vel.extend(item["value"]) + d_vel.extend(d_item) elif item.get("channel", None) == axis-1 and item.get("name", None) == "device_servo_trq_feedback": - d_trq.extend(item["value"]) + d_trq.extend(d_item) elif item.get("channel", None) == 0 and item.get("name", None) == "device_safety_estop": - d_stop.extend(item["value"]) + d_stop.extend(d_item) df1 = pandas.DataFrame.from_dict({"hw_joint_vel_feedback": d_vel}) df2 = pandas.DataFrame.from_dict({"device_servo_trq_feedback": d_trq}) df3 = pandas.DataFrame.from_dict({"device_safety_estop": d_stop}) df = pandas.concat([df1, df2, df3], axis=1) - filename = f"{path}\\j{axis}\\reach{reach}_load{load}_speed{speed}\\reach{reach}_load{load}_speed{speed}_{rounds}.data" + filename = f"{path}/j{axis}/reach{reach}_load{load}_speed{speed}/reach{reach}_load{load}_speed{speed}_{rounds}.data" df.to_csv(filename, sep="\t", index=False) def run_rl(path, sub, hr, md, config_file, prj_file, result_dirs, avs, w2t): - count, total = 0, 63 + count, total, speed_target = 0, 63, 0 prj_name = prj_file.split("/")[-1].split(".")[0] display_pdo_params = [{"name": name, "channel": chl} for name in ["hw_joint_vel_feedback", "device_servo_trq_feedback"] for chl in range(6)] display_pdo_params.append({"name": "device_safety_estop", "channel": 0}) @@ -119,7 +123,9 @@ def run_rl(path, sub, hr, md, config_file, prj_file, result_dirs, avs, w2t): get_init_speed = float(ws.cell(row=3, column=2).value) single_brake = str(ws.cell(row=4, column=2).value) pon = ws.cell(row=5, column=2).value - w2t(f"write_diagnosis = {write_diagnosis}, get_init_speed = {get_init_speed}, single_brake = {single_brake}\n") + io_name = ws.cell(row=6, column=2).value.upper() + wb.close() + w2t(f"基本参数配置:write_diagnosis = {write_diagnosis}, get_init_speed = {get_init_speed}, single_brake = {single_brake}, pon = {pon}\n") if pon == "positive": md.write_pon(1) @@ -136,7 +142,7 @@ def run_rl(path, sub, hr, md, config_file, prj_file, result_dirs, avs, w2t): speed = condition.split("_")[2].removeprefix("speed") # for single condition test - single_axis = 0 + single_axis = -1 if single_brake != "0": total = 3 single_axis = int(single_brake.split("-")[0]) @@ -145,25 +151,28 @@ def run_rl(path, sub, hr, md, config_file, prj_file, result_dirs, avs, w2t): for axis in range(1, 4): # for single condition test - if (single_axis != 0 and single_axis != axis) or (axis == 3 and reach != "100"): + if (single_axis != -1 and single_axis != axis) or (axis == 3 and reach != "100"): continue md.write_axis(axis) w2t(f"-"*90+"\n", "purple") for rounds in range(1, 4): count += 1 + _ = 3 if count % 3 == 0 else count % 3 this_time = time.strftime("%Y-%m-%d %H:%M:%S", time.localtime(time.time())) prj_path = f"{prj_name}/_build/{prj_name}.prj" - w2t(f"[{this_time} | {count}/{total}] 正在执行 {axis} 轴 {condition} 的第 {count} 次制动测试...\n") + w2t(f"[{this_time} | {count}/{total}] 正在执行 {axis} 轴 {condition} 的第 {_} 次制动测试...\n") # 1. 触发软急停,并解除,目的是让可能正在运行着的机器停下来,切手动模式并下电 - md.trigger_estop() - md.reset_estop() - md.clear_alarm() + md.r_soft_estop(0) + md.r_soft_estop(1) + clibs.c_ec.setdo_value(io_name, "true") + md.r_reset_estop() + md.r_clear_alarm() md.write_act(0) - time.sleep(write_diagnosis) # 软急停超差后,等待写诊断时间,可通过configs.xlsx配置 + time.sleep(write_diagnosis) # 急停超差后,等待写诊断时间,可通过configs.xlsx配置,2.3 版本之后设置为 0 即可 - while count == 1: + while count % 3 == 1: # 2. 修改要执行的场景 rl_cmd = "" ssh = paramiko.SSHClient() @@ -176,24 +185,24 @@ def run_rl(path, sub, hr, md, config_file, prj_file, result_dirs, avs, w2t): rl_speed = f"VelSet {speed}" rl_tool = f"tool p_tool = tool{sub.removeprefix("tool")}" cmd = "cd /home/luoshi/bin/controller/; " - cmd += 'sudo sed -i "/brake_E/d" projects/target/_build/brake/main.mod; ' - cmd += f'sudo sed -i "/DONOTDELETE/i {rl_cmd}" projects/target/_build/brake/main.mod; ' - cmd += 'sudo sed -i "/VelSet/d" projects/target/_build/brake/main.mod; ' - cmd += f'sudo sed -i "/MoveAbsJ/i {rl_speed}" projects/target/_build/brake/main.mod; ' - cmd += 'sudo sed -i "/tool p_tool/d" projects/target/_build/brake/main.mod; ' - cmd += f'sudo sed -i "/VelSet/i {rl_tool}" projects/target/_build/brake/main.mod; ' + cmd += f'sudo sed -i "/brake_E/d" projects/{prj_name}/_build/brake/main.mod; ' + cmd += f'sudo sed -i "/DONOTDELETE/i {rl_cmd}" projects/{prj_name}/_build/brake/main.mod; ' + cmd += f'sudo sed -i "/VelSet/d" projects/{prj_name}/_build/brake/main.mod; ' + cmd += f'sudo sed -i "/MoveAbsJ/i {rl_speed}" projects/{prj_name}/_build/brake/main.mod; ' + cmd += f'sudo sed -i "/tool p_tool/d" projects/{prj_name}/_build/brake/main.mod; ' + cmd += f'sudo sed -i "/VelSet/i {rl_tool}" projects/{prj_name}/_build/brake/main.mod; ' stdin, stdout, stderr = ssh.exec_command(cmd, get_pty=True) stdin.write(clibs.password + "\n") stdout.read().decode() # 需要read一下才能正常执行 stderr.read().decode() # 3. reload工程后,pp2main,并且自动模式和上电,最后运行程序 - hr.execution("overview.reload", prj_path=prj_path, tasks=["brake", "stop0_related"]) - hr.execution("rl_task.pp_to_main", tasks=["brake", "stop0_related"]) + hr.execution("overview.reload", prj_path=prj_path, tasks=["brake"]) + hr.execution("rl_task.pp_to_main", tasks=["brake"]) hr.execution("state.switch_auto") hr.execution("state.switch_motor_on") hr.execution("rl_task.set_run_params", loop_mode=True, override=1.0) - hr.execution("rl_task.run", tasks=["brake", "stop0_related"]) + hr.execution("rl_task.run", tasks=["brake"]) t_start = time.time() while True: if md.read_ready_to_go() == 1: @@ -201,21 +210,24 @@ def run_rl(path, sub, hr, md, config_file, prj_file, result_dirs, avs, w2t): break else: time.sleep(1) - if (time.time() - t_start) // 20 > 1: + if (time.time() - t_start) > 20: w2t("20s 内未收到机器人的运行信号,需要确认 RL 程序编写正确并正常执行...", "red", "ReadySignalTimeoutError") # 4. 找出最大速度,传递给RL程序,最后清除相关记录 + time.sleep(10) # 消除前 10s 的不稳定数据 + start_time = time.strftime("%Y-%m-%d %H:%M:%S", time.localtime(time.time())) time.sleep(get_init_speed) # 指定时间后获取实际【正|负】方向的最大速度,可通过configs.xlsx配置 - clibs.execution("rl_task.stop", tasks=["brake"]) + end_time = time.strftime("%Y-%m-%d %H:%M:%S", time.localtime(time.time())) + hr.execution("rl_task.stop", tasks=["brake"]) + time.sleep(5) # 确保数据都拿到 # 找出最大速度 @clibs.db_lock def get_speed_max(): _speed_max = 0 - len_records = int(get_init_speed * 20) + 1 # 1000 / 50 = 20 - clibs.cursor.execute(f"select content from logs where content like 'diagnosis.result' limit {len_records}") + clibs.cursor.execute(f"select content from logs where time between '{start_time}' and '{end_time}' and content like '%diagnosis.result%' order by id asc") records = clibs.cursor.fetchall() for record in records: - data = eval(record)["data"] + data = eval(record[0])["data"] for item in data: if item.get("channel", None) == axis-1 and item.get("name", None) == "hw_joint_vel_feedback": _ = clibs.RADIAN * sum(item["value"]) / len(item["value"]) @@ -234,20 +246,17 @@ def run_rl(path, sub, hr, md, config_file, prj_file, result_dirs, avs, w2t): md.write_speed_max(speed_max) if speed_max < 10: - md.clear_alarm() + md.r_clear_alarm() w2t("未获取到正确的速度,即将重新获取...\n", "red") continue else: break - # 5. 清除软急停,重新运行程序,并打开曲线发送继续运动信号,当速度达到最大值时,通过DO触发急停 - md.reset_estop() # 其实没必要 - md.clear_alarm() - - hr.execution("rl_task.pp_to_main", tasks=["brake", "stop0_related"]) + # 5. 重新运行程序,发送继续运动信号,当速度达到最大值时,通过DO触发急停 + hr.execution("rl_task.pp_to_main", tasks=["brake"]) hr.execution("state.switch_auto") hr.execution("state.switch_motor_on") - hr.execution("rl_task.run", tasks=["brake", "stop0_related"]) + hr.execution("rl_task.run", tasks=["brake"]) for i in range(3): if md.read_ready_to_go() == 1: md.write_act(1) @@ -258,21 +267,38 @@ def run_rl(path, sub, hr, md, config_file, prj_file, result_dirs, avs, w2t): w2t("3s 内未收到机器人的运行信号,需要确认 RL 程序配置正确并正常执行...", "red", "ReadySignalTimeoutError") time.sleep(10) # 排除从其他位姿到零点位姿,再到轴极限位姿的时间 - md.write_probe(1) - t_start = time.time() - while True: - if md.read_brake_done() == 1: - time.sleep(4) # 保证速度归零 - md.write_probe(0) - break - else: - time.sleep(1) - if (time.time() - t_start) > 30: - md.write_probe(0) - w2t(f"30s 内未触发急停,该条数据无效,需要确认 RL/Python 程序配置正确并正常执行,或者判别是否是机器本体问题,比如正负方向速度是否一致...", "red", "NoEstopTriggeredError") + def exec_brake(): + flag, start, data, record = True, time.time(), None, None + while flag: + time.sleep(0.2) + if time.time() - start > 20: + w2t("20s 内未触发急停,需排查......", "red", "BrakeTimeoutError") + + try: + clibs.lock.acquire(True) + clibs.cursor.execute(f"select content from logs where content like '%diagnosis.result%' order by id desc limit 1") + record = clibs.cursor.fetchone() + data = eval(record[0])["data"] + finally: + clibs.lock.release() + + for item in data: + if item.get("channel", None) != axis-1 or item.get("name", None) != "hw_joint_vel_feedback": + continue + + speed_moment = clibs.RADIAN * sum(item["value"]) / len(item["value"]) + if (pon == "positive" and speed_moment > 0) or (pon == "negative" and speed_moment < 0): + if abs(speed_moment) > speed_target * 0.95: + clibs.c_ec.setdo_value(io_name, "false") + time.sleep(5) + flag = False + break + return time.time() + + t_end = exec_brake() # 6. 保留数据并处理输出 - gen_result_file(path, axis, reach, load, speed, rounds) + gen_result_file(path, axis, t_end, reach, load, speed, rounds) else: w2t(f"\n{sub.removeprefix("tool")}%负载的制动性能测试执行完毕,如需采集其他负载,须切换负载类型,并更换其他负载,重新执行。\n", "green") hr.execution("diagnosis.open", open=False, display_open=False, overrun=True, turn_area=True, delay_motion=False) @@ -280,21 +306,22 @@ def run_rl(path, sub, hr, md, config_file, prj_file, result_dirs, avs, w2t): def main(): - # path, hr, md, loadsel, w2t + s_time = time.time() path = clibs.data_at["_path"] sub = clibs.data_at["_sub"] w2t = clibs.w2t hr = clibs.c_hr md = clibs.c_md - s_time = time.time() data_dirs, data_files = clibs.traversal_files(path, w2t) - config_file, reach33, reach66, reach100, prj_file, result_dirs, avs = initialization(path, sub, data_dirs, data_files, hr, w2t) + config_file, prj_file, result_dirs, avs = initialization(path, sub, data_dirs, data_files, hr, w2t) clibs.c_pd.push_prj_to_server(prj_file) run_rl(path, sub, hr, md, config_file, prj_file, result_dirs, avs, w2t) + e_time = time.time() time_total = e_time - s_time - w2t(f"处理总时长:{time_total // 3600:02.0f} h {time_total % 3600 // 60:02.0f} m {time_total % 60:02.0f} s", "green") + w2t(f"-" * 90 + "\n", "purple") + w2t(f"处理总时长:{time_total // 3600:02.0f} h {time_total % 3600 // 60:02.0f} m {time_total % 60:02.0f} s\n", "green") if __name__ == "__main__": diff --git a/code/automatic_test/do_current.py b/code/automatic_test/do_current.py index a95ba0e..c29595d 100644 --- a/code/automatic_test/do_current.py +++ b/code/automatic_test/do_current.py @@ -201,7 +201,7 @@ def run_rl(path, prj_file, hr, md, sub, w2t): # 4. 执行采集 time.sleep(10) # 消除前 10s 的不稳定数据 start_time = time.strftime("%Y-%m-%d %H:%M:%S", time.localtime(time.time())) - single_time, stall_time, scenario_time = 30, 10, 0 + single_time, stall_time, scenario_time = 40, 10, 0 if number < 6: # 单轴 time.sleep(single_time) elif number < 12: # 堵转 @@ -234,6 +234,7 @@ def run_rl(path, prj_file, hr, md, sub, w2t): def main(): + s_time = time.time() path = clibs.data_at["_path"] sub = clibs.data_at["_sub"] w2t = clibs.w2t @@ -245,6 +246,11 @@ def main(): clibs.c_pd.push_prj_to_server(prj_file) run_rl(path, prj_file, hr, md, sub, w2t) + e_time = time.time() + time_total = e_time - s_time + w2t(f"-" * 90 + "\n", "purple") + w2t(f"处理总时长:{time_total // 3600:02.0f} h {time_total % 3600 // 60:02.0f} m {time_total % 60:02.0f} s", "green") + if __name__ == "__main__": main() diff --git a/code/common/openapi.py b/code/common/openapi.py index 4717469..02cea4d 100644 --- a/code/common/openapi.py +++ b/code/common/openapi.py @@ -11,7 +11,7 @@ import time from common import clibs from os import listdir -from pymodbus.payload import BinaryPayloadDecoder, BinaryPayloadBuilder +from pymodbus.payload import BinaryPayloadBuilder from pymodbus.constants import Endian import os.path from ctypes import * @@ -161,17 +161,13 @@ class ModbusRequest(object): clibs.insert_logdb("INFO", "openapi", f"modbus: 40102 将 {pon} 写入") def write_axis(self, axis): - builder = BinaryPayloadBuilder(byteorder=Endian.BIG, wordorder=Endian.LITTLE) - builder.add_32bit_int(int(axis)) - payload = builder.to_registers() - self.__c.write_registers(40103, payload) + result = self.__c.convert_to_registers(int(axis), self.__c.DATATYPE.INT32, word_order="little") + self.__c.write_registers(40103, result) clibs.insert_logdb("INFO", "openapi", f"modbus: 40103 将 {axis} 写入") def write_speed_max(self, speed): - builder = BinaryPayloadBuilder(byteorder=Endian.BIG, wordorder=Endian.LITTLE) - builder.add_32bit_float(float(speed)) - payload = builder.build() - self.__c.write_registers(40105, payload, skip_encode=True) + result = self.__c.convert_to_registers(float(speed), self.__c.DATATYPE.FLOAT32, word_order="little") + self.__c.write_registers(40105, result) clibs.insert_logdb("INFO", "openapi", f"modbus: 40105 将 {speed} 写入") def r_write_signals(self, addr: int, value): # OK | 40100 - 40109: signal_0 ~ signal_9 @@ -878,1001 +874,1007 @@ class HmiRequest(object): # =================================== ↓↓↓ specific functions ↓↓↓ =================================== - # def switch_motor_state(self, state: str): # OK - # """ - # 切换上电/下电的状态 - # :param state: on/off - # :return: None - # """ - # match state: - # case "on": - # self.execution("state.switch_motor_on") - # case "off": - # self.execution("state.switch_motor_off") - # case _: - # clibs.insert_logdb("ERROR", "openapi", f"hr: switch_motor_state 参数错误 {state}: 非法参数,只接受 on/off") - # - # def switch_operation_mode(self, mode: str): # OK - # """ - # 切换自动/手动操作模式 - # :param mode: auto/manual - # :return: None - # """ - # match mode: - # case "auto": - # self.execution("state.switch_auto") - # case "manual": - # self.execution("state.switch_manual") - # case _: - # clibs.insert_logdb("ERROR", "openapi", "hr: switch_operation_mode 参数错误 非法参数,只接受 auto/manual") - # - # def reload_project(self, prj_name: str, tasks: list): # OK - # """ - # 重新加载指定工程 - # :param prj_name: 工程名,也即 zip 文件的名字 - # :param tasks: 要加载的任务列表 - # :return: None - # """ - # prj_path = f"{prj_name}/_build/{prj_name}.prj" - # self.execution("overview.reload", prj_path=prj_path, tasks=tasks) - # - # def set_project_auto_reload(self, prj_name: str): # OK - # """ - # 将指定工程设置为开机自动加载,也即默认工程 - # :param prj_name: 工程名,也即 zip 文件的名字 - # :return: None - # """ - # autoload_prj_path = f"{prj_name}/_build/{prj_name}.prj" - # self.execution("overview.set_autoload", autoload_prj_path=autoload_prj_path) - # - # def pp_to_main(self, tasks: list): # OK - # """ - # 将指定的任务列表的指针,指向 main 函数 - # :param tasks: 任务列表 - # :return: None - # """ - # self.execution("rl_task.pp_to_main", tasks=tasks) - # - # def program_start(self, tasks: list): # OK - # """ - # 开始执行程序任务,必须是自动模式下执行 - # :param tasks: 任务列表 - # :return: None - # """ - # self.execution("rl_task.run", tasks=tasks) - # - # def program_stop(self, tasks: list): # OK - # """ - # 停止执行程序任务 - # :param tasks: 人物列表 - # :return: None - # """ - # self.execution("rl_task.stop", tasks=tasks) - # - # def set_program_loop_speed(self, loop_mode: bool = True, override: float = 0.5): # OK - # """ - # :param loop_mode: True为循环模式,False为单次模式 - # :param override: HMI 左下方的速度滑块,取值范围 [0, 1] - # :return: None - # """ - # self.execution("rl_task.set_run_params", loop_mode=loop_mode, override=override) - # - # def clear_alarm(self): # OK - # """ - # 清除伺服告警 - # :return: None - # """ - # self.execution("servo.clear_alarm") - # - # def reboot_robot(self): # OK - # """ - # 重启控制器 - # :return: None - # """ - # self.execution("controller.reboot") - # clibs.insert_logdb("INFO", "openapi", f"hr: 控制器重启中,重连预计需要等待 100s 左右...") - # ts = time() - # time.sleep(30) - # while True: - # time.sleep(5) - # te = time() - # if te - ts > 180: - # self.__silence = False - # self.__sth_wrong("3min 内未能完成重新连接,需要查看后台控制器是否正常启动,或者 ip/port 是否正确") - # break - # for _ in range(3): - # if not self.__is_connected: - # break - # time.sleep(2) - # else: - # clibs.insert_logdb("INFO", "openapi", "hr: HMI 重新连接成功...") - # break - # - # def reload_io(self): - # """ - # 触发控制器重新加载 IO 设备列表 - # :return: None - # """ - # self.execution("io_device.load_cfg") - # - # @property - # def get_quickturn_pos(self): # OK - # """ - # 获取机器人的home位姿、拖动位姿和发货位姿,轴关节角度,end_posture 取值如下: - # 0 法兰平面与地面平行 - # 1 工具坐标系X轴与地面垂直,正向朝下 - # 2 工具坐标系X轴与地面垂直,正向朝上 - # 3 工具坐标系Y轴与地面垂直,正向朝下 - # 4 工具坐标系Y轴与地面垂直,正向朝上 - # 5 工具坐标系Z轴与地面垂直,正向朝下 - # 6 工具坐标系Z轴与地面垂直,正向朝上 - # :return: as below - # { - # "enable_home": false, // 是否开启 home 点快速调整 - # "enable_drag": false, // 是否开启拖动位姿点快速调整 - # "enable_transport": false, // 是否开启发货位姿点快速调整 - # "joint_home": [0.0,0.0,0.0,0.0,0.0,0.0,0.0], // home 位姿的关节角度 - # "joint_drag": [0.0,0.0,0.0,0.0,0.0,0.0,0.0], // 拖动位姿的关节角度 - # "joint_transport": [0.0,0.0,0.0,0.0,0.0,0.0,0.0], // 发货位姿的关节角度 - # "end_posture":0, // 末端姿态的调整方式,取值 0-6 - # "home_error_range":[0.0,0.0,0.0,0.0,0.0,0.0,0.0] // home点误差范围 - # } - # """ - # return self.__get_data(currentframe().f_code.co_name, "move.get_quickturn_pos") - # - # def set_quickturn_pos(self, enable_home: bool = False, enable_drag: bool = False, enable_transport: bool = False, end_posture: int = 0): # OK - # """ - # 设置机器人的home位姿、拖动位姿、发货位姿,轴关节角度,Home点误差范围,详见上一个 get_quickturn_pos 功能实现 - # :param enable_home: 是否开启 home 点快速调整 - # :param enable_drag: 是否开启拖动位姿点快速调整 - # :param enable_transport:是否开启发货位姿点快速调整 - # :param end_posture: 末端姿态的调整方式,取值 0-6,详见 get_quickturn_pos 注释 - # :return: None - # """ - # self.execution("move.set_quickturn_pos", enable_home=enable_home, enable_drag=enable_drag, enable_transport=enable_transport, end_posture=end_posture) - # - # def move2quickturn(self, name: str): # OK - # """ - # 运动到指定的快速调整位姿 - # :param name: 指定快速调整的名称,home/drag/transport - # :return: None - # """ - # self.execution("move.quick_turn", name=name) - # - # def stop_move(self, stoptype=0): # OK - # """ - # 停止运动 - # TS_READY | TS_JOG | TS_LOADIDENTIFY | TS_DYNAMICIDENTIFY | TS_DRAG | TS_PROGRAM | TS_DEMO | TS_RCI | TS_DEBUG | TS_FRICTIONIDENTIFY - # :param stoptype: 对应控制器的任务空间类型TaskSpace的枚举值,0-7 - # :return: None - # """ - # self.execution("move.stop", stoptype=stoptype) - # - # @property - # def get_jog_params(self): # OK - # """ - # 获取JOG的参数 - # 世界坐标系 WORLD_COORDINATE 0 - # 法兰盘坐标系 FLANGE_COORDINATE 1 - # 基坐标系 BASE_COORDINATE 2 - # 工具坐标系 TOOL_COORDINATE 3 - # 工件坐标系 FRAME_COORDINATE 4 - # 关节空间 JOINT_SPACE 5 - # :return: - # { - # "step": 1000 [1000-连续] [10/1/0.1/0.001-点动] - # "override": 0.2 速度比率 - # "space": 5 JOG的空间 - # } - # """ - # return self.__get_data(currentframe().f_code.co_name, "jog.get_params") - # - # def set_jog_params(self, step, override, space): # OK - # """ - # 设置JOG的参数,包含步长,空间,速度倍率 - # :param step: [1000-连续] [10/1/0.1/0.001-点动] - # :param override: 速度比率 - # :param space: JOG的空间 - # :return: None - # """ - # self.execution("jog.set_params", step=step, override=override, space=space) - # - # def start_jog(self, index: int, direction: bool = False, is_ext: bool = False): # OK - # """ - # 开始 JOG 运动 - # :param index: 0-6,若选轴空间,则 0-6 对应 1-7 轴,若选笛卡尔空间,则 0-6 对应 xyzabc elb - # :param direction: True 正方向,False 反方向 - # :param is_ext: 是否是外部轴 jog - # :return: None - # """ - # self.execution("jog.start", index=index, direction=direction, is_ext=is_ext) - # - # @property - # def get_socket_params(self): # OK - # """ - # 获取socket参数 - # :return: - # { - # "auto_connect": true, // True 开机启动,False 不开机启动 - # "disconnection_detection_time": 10, // 链接断开检测周期(s) - # "disconnection_triggering_behavior": 0, // 断开连接触发行为 0无动作 1暂停程序 2暂停并下电 - # "enable": true, // True 开启或者 False 关闭 - # "ip": "", // 仅限于客户端,用于指定服务端 IP;当作为服务端时,该参数设置为空字符串,否则会报错!!! - # "name": "name", // 连接名称 - # "port": "8080", // 连接端口 - # "reconnect_flag": true, // True 自动重连,False 不自动重连 - # "suffix": "\r", // 指定发送分隔符 - # "type": 1 // 连接类型 0 client | 1 server - # } - # """ - # return self.__get_data(currentframe().f_code.co_name, "socket.get_params") - # - # def set_socket_params(self, enable: bool, port: str, suffix: str, type: int = 1, **kwargs): # OK - # """ - # 设置 socket 参数,一般作为服务器使用 - # :param enable: True 开启或者 False 关闭 - # :param port: 连接端口 - # :param suffix: 指定发送分隔符 - # :param type: 0 client | 1 server - # :return: None - # """ - # data = self.get_socket_params - # keys = data.keys() - # kwargs.update({"enable": enable, "port": port, "suffix": suffix, "type": type}) - # for _ in keys: - # if _ in kwargs.keys(): - # data[_] = kwargs[_] - # self.execution("socket.set_params", data=data) - # - # @property - # def get_diagnosis_params(self, version="1.4.1"): # OK - # """ - # 获取诊断功能开启状态,以及相应其他信息 - # :param version: 指定诊断工具版本 - # :return: - # { - # "delay_motion": false, // - - # "display_open": false, // 诊断显示功能开启状态 - # "ecat_diagnosis_state": false, // - - # "overrun": false, // 是否开启实时线程超时监控上报 - # "pdo_params": [...], // 指定版本支持的所有曲线信息 - # "state": true, // 诊断功能的开启状态 - # "turn_area": false // 转弯区是否上报 - # } - # """ - # return self.__get_data(currentframe().f_code.co_name, "diagnosis.get_params", version=version) - # - # def set_diagnosis_params(self, display_pdo_params: list, frequency: int = 50, version: str = "1.4.1"): # OK - # """ - # 设置诊断功能显示参数 [{"name": "hw_joint_vel_feedback", "channel": 0}, ] - # :param display_pdo_params: 指定要采集的曲线名称,具体可通过 get_diagnosis_params 函数功能获取所有目前已支持的曲线 - # :param frequency: 采样频率,默认 50ms - # :param version: xDiagnose的版本号 - # :return: None - # """ - # self.execution("diagnosis.set_params", display_pdo_params=display_pdo_params, frequency=frequency, version=version) - # - # def open_diagnosis(self, open: bool, display_open: bool, overrun: bool = False, turn_area: bool = False, delay_motion: bool = False): # OK - # """ - # 打开或者关闭诊断曲线,并定义其他功能的开关(调试相关功能,比如是否开启线程超时监控和上报,转弯区以及运动延迟等) - # :param open: 诊断功能,控制HMI->日志->诊断设置->私服诊断开关,一般设置成 True - # :param display_open: 诊断显示功能,指的是在线诊断插件中的打开 switch 的状态,需要诊断数据的情况,设置成 True - # :param overrun: 实时线程超时监控上报 - # :param turn_area: 转弯区上报 - # :param delay_motion: 延迟运动 - # :return: None - # """ - # self.execution("diagnosis.open", open=open, display_open=display_open, overrun=overrun, turn_area=turn_area, delay_motion=delay_motion) - # - # def save_diagnosis(self, save: bool = True): # OK - # """ - # 保存诊断数据,也就是主动写诊断动作,HMI日志->诊断设置->保存诊断数据 - # :param save: 保存数据开关 - # :return: None - # """ - # self.execution("diagnosis.save", save=save) - # - # @property - # def qurry_system_io_configuration(self): # OK - # """ - # 系统IO配置的查询协议,trigger 参数取值参照如下: - # FLANKS 0, //边缘触发 - # POS_FLANK 1, //上升沿 - # NEG_FLANK 2, //下降沿 - # HIGH_LEVEL 3, //高电平 - # LOW_LEVEL 4 //低电平 - # :return: - # { - # "input_system_io": { - # "motor_on": { - # "signal":"DI0_0", - # "trigger":1 - # }, - # "motor_off": { - # "signal":"DI0_0", - # "trigger":2 - # } - # }, - # "output_system_io": { - # "sta_motor_on": { - # "signal":"DO0_0" - # }, - # "sta_robot_running": { - # "signal":"DO0_1" - # } - # } - # } - # """ - # return self.__get_data(currentframe().f_code.co_name, "system_io.query_configuration") - # - # @property - # def qurry_system_io_event_configuration(self): # OK - # """ - # 查询当前系统支持的系统IO事件列表,包括事件key、名称、支持的触发方式等配置 - # :return: - # { - # "input_system_event": [ - # { - # "key": "ctrl_motor_on", - # "name": "上电", - # "trigger_types": [ - # 1, - # 2 - # ] - # }, - # { - # "key": "ctrl_motor_off", - # "name": "下电", - # "trigger_types": [ - # 1, - # 2 - # ] - # } - # ], - # "output_system_event": [ - # { - # "key": "sta_motor_on", - # "name": "上下电状态" - # }, - # { - # "key": "sta_program", - # "name": "运行状态" - # } - # ], - # "input_mutex_event": [ - # { - # "key0": "ctrl_motor_on", - # "key1": "ctrl_motor_off" - # }, - # { - # "key0": "ctrl_switch_auto", - # "key1": "ctrl_switch_manu" - # } - # ] - # } - # """ - # return self.__get_data(currentframe().f_code.co_name, "system_io.query_configuration") - # - # def update_system_io_configuration(self, i_funcs: list, o_funcs: list, i_signals: list, o_signals: list, trig_types: list): # OK - # """ - # 配置系统 IO - # :param i_funcs: 输入,只写功能码列表 - # :param o_funcs: 输出,只读功能码列表 - # :param i_signals: DI 信号列表 - # :param o_signals: DO 信号列表 - # :param trig_types: 触发条件列表,可参考 qurry_system_io_configuration 中的触发条件 - # :return: None - # """ - # input_system_io, output_system_io = {}, {} - # for i_func in i_funcs: - # _index = i_funcs.index(i_func) - # input_system_io[i_func] = {"signal": i_signals[_index], "trigger": trig_types[_index]} - # for o_func in o_funcs: - # _index = o_funcs.index(o_func) - # output_system_io[o_func] = {"signal": o_signals[_index]} - # self.execution("system_io.update_configuration", input_system_io=input_system_io, output_system_io=output_system_io) - # - # @property - # def get_fieldbus_device_params(self): # OK - # """ - # 获取的是 HMI通讯->总线设备列表的信息,以及开关状态 - # :return: - # { - # "device_list": [ - # { - # "device_name": "modbus_1", - # "enable": true - # }, { - # "device_name": "modbus_2", - # "enable": false - # } - # ] - # } - # """ - # return self.__get_data(currentframe().f_code.co_name, "fieldbus_device.get_params") - # - # def set_fieldbus_device_params(self, device_name: str, enable: bool): # OK - # """ - # 定义开关设备的协议,一次只能打开一个设备 - # :param device_name: 设备列表中的名称 - # :param enable: 是否开启,这里操作的是 HMI通信->IO设备里面的开关状态 - # :return: None - # """ - # self.execution("fieldbus_device.set_params", device_name=device_name, enable=enable) - # - # def reload_fieldbus(self): # OK - # """ - # 触发控制器重新加载总线设备 - # :return: None - # """ - # self.execution("fieldbus_device.load_cfg") - # - # @property - # def get_modbus_params(self): # OK - # """ - # 获取modbus参数 - # :return: - # { - # "connect_state": true, - # "enable_master": false, - # "enable_slave": false, - # "ip": "192.168.0.160", - # "is_convert": true, - # "port": 502, - # "slave_id": 1 - # } - # """ - # return self.__get_data(currentframe().f_code.co_name, "modbus.get_params") - # - # def set_modbus_params(self, enable_slave: bool, ip: str, port: int, slave_id: int, enable_master: bool): # OK - # """ - # 设置modbus参数,相当于新建 - # :param enable_slave: Modbus从站是否自动开启 - # :param ip: ip 地址 - # :param port: 端口 - # :param slave_id: 从站 ID - # :param enable_master: Modbus主站是否自动开启 - # :return: - # """ - # self.execution("modbus.set_params", enable_slave=enable_slave, ip=ip, port=port, slave_id=slave_id, enable_master=enable_master) - # - # def reload_registers(self): # OK - # """ - # 触发控制器重新加载寄存器列表 - # :return: None - # """ - # self.execution("modbus.load_cfg") - # - # def get_modbus_values(self, mode: str = "all"): # OK - # """ - # 用于获取 modbus 寄存器变量值的更新信息,展示在状态监控界面 - # :param mode: all/change - # :return: - # """ - # return self.__get_data(currentframe().f_code.co_name, "modbus.get_values", mode=mode) - # - # @property - # def get_soft_limit_params(self): # OK - # """ - # 获取软限位参数 - # :return: - # { - # "enable":true - # "upper":[0,0,0,0,0,0,0], - # "lower":[0,0,0,0,0,0,0], - # "reduced_upper":[0,0,0,0,0,0,0], - # "reduced_lower":[0,0,0,0,0,0,0] - # } - # """ - # return self.__get_data(currentframe().f_code.co_name, "soft_limit.get_params") - # - # def set_soft_limit_params(self, **kwargs): # OK - # """ - # 设定软限位参数 enable: bool, upper: list, lower: list, reduced_upper: list, reduced_lower: list - # :enable: 是否启用软限位 - # :upper: 软限位上限 - # :lower: 软限位下限 - # :reduced_upper: 缩减模式软限位上限 - # :reduced_lower: 缩减模式软限位下限 - # :return: None - # """ - # data = self.get_soft_limit_params - # keys = data.keys() - # for _ in keys: - # if _ in kwargs.keys(): - # data[_] = kwargs[_] - # self.execution("soft_limit.set_params", data=data) - # - # @property - # def get_device_params(self): # OK - # """ - # 获取设备信息 - # :return: - # """ - # return self.__get_data(currentframe().f_code.co_name, "device.get_params") - # - # @property - # def get_cart_pos(self): # OK - # """ - # 获取机器人的当前位姿:包括轴关节角度,笛卡尔关节角度,四元数,欧拉角(臂角) - # :return: - # { - # "joint":[0.0,0.0,0.0,0.0,0.0,0.0], - # "position":[0.0,0.0,0.0,0.0,0.0,0.0], - # "euler":[0.0,0.0,0.0], - # "quaternion"[0.0,0.0,0.0,0.0], - # "elb":0.0, // 可缺省 - # "ext_joint":[0.0,0.0,0.0,0.0,0.0] - # } - # """ - # return self.__get_data(currentframe().f_code.co_name, "move.get_pos") - # - # @property - # def get_joint_pos(self): # OK - # """ - # 获取机器人的当前关节角度:包括内部轴和外部轴 - # :return: - # { - # "inner_pos": [0,0,0,0,0,0,0], - # "extern_pos": [0,0,0,0,0,0,0] - # } - # """ - # return self.__get_data(currentframe().f_code.co_name, "move.get_joint_pos") - # - # @property - # def get_monitor_cfg(self): # OK - # """ - # 获取机器人的监控配置参数,RefCoordinateType 类型数据,表示当前控制器位置监测的相对坐标系 - # 基坐标系 REF_COORDINATE_BASE 0 - # 世界坐标系 REF_COORDINATE_WORLD 1 - # 工件坐标系 REF_COORDINATE_WOBJ 2 - # :return: - # { - # "ref_coordinate": 0 - # } - # """ - # return self.__get_data(currentframe().f_code.co_name, "move.get_monitor_cfg") - # - # def set_monitor_cfg(self, ref_coordinate): # OK - # """ - # 设置机器人的监控配置参数 - # :ref_coordinate: RefCoordinateType类型数据,用来设置当前控制器位置监测的相对坐标系 - # :return: None - # """ - # self.execution("move.set_monitor_cfg", ref_coordinate=ref_coordinate) - # - # @property - # def get_move_params(self): # OK - # """ - # 获取机器人的运动参数:包括减速比、耦合比、最大速度、加速度、加加速度、acc ramp time、规划步长等信息 - # :return: - # { - # "MOTION": { - # "ACC_RAMPTIME_JOG": 0.5, - # "ACC_RAMPTIME_STOP": 0.5, - # "DEFAULT_ACC_PARAMS": [1.0, 0.5], - # "JERK_LIMIT_CART": 0, - # "JERK_LIMIT_JOINT": 0, - # "JERK_LIMIT_ROT": 0, - # "JOINT_MAX_ACC": [500, 500, 1000, 1000, 1000], - # "JOINT_MAX_JERK": [2000, 2000, 2000, 4000, 4000, 4000], - # "JOINT_MAX_SPEED": [120.0, 120.0, 180.0, 180.0, 180.0, 180.0], - # "MAX_ACC_PARAMS": [1.0, 1], - # "MIN_ACC_PARAMS": [0.3, 0.05], - # "TCP_MAX_ACC": 5000, - # "TCP_MAX_JERK": 10000, - # "TCP_MAX_SPEED": 1000, - # "TCP_ROTATE_MAX_ACC": 1800, - # "TCP_ROTATE_MAX_JERK": 3600, - # "TCP_ROTATE_MAX_SPEED": 180, - # "VEL_SMOOTH_FACTOR": 1.0, - # "VEL_SMOOTH_FACTOR_RANGE": [1.0, 10.0] - # } - # } - # """ - # return self.__get_data(currentframe().f_code.co_name, "move.get_params") - # - # def set_move_params(self, **kwargs): # OK - # """ - # 设置机器人的运动参数:轴最大速度、轴最大加加速度、速度、加加速度、加速度、加加速度、acc ramp time、规划步长等信息 - # 可选参数:参考 get_move_params 函数返回值 MOTION 里面的选项 - # :return: None - # """ - # data = self.get_move_params["MOTION"] - # print(f"res = {data}") - # keys = data.keys() - # for _ in keys: - # if _ in kwargs.keys(): - # data[_] = kwargs[_] - # self.execution("move.set_params", data=data) - # - # @property - # def get_quick_stop_distance(self): # OK - # """ - # 获取机器人 search 指令最大停止距离 - # :return: - # { - # "distance":2.0 - # } - # """ - # return self.__get_data(currentframe().f_code.co_name, "move.get_quickstop_distance") - # - # def set_quick_stop_distance(self, distance: float): # OK - # """ - # 设置机器人 search 指令最大停止距离 - # :param distance: 停止距离,单位 mm - # :return: None - # """ - # self.execution("move.set_quickstop_distance", distance=distance) - # - # @property - # def get_collision_params(self): # OK - # """ - # 获取碰撞检测相关参数 - # :return: - # { - # "action": 1, // 触发行为:1-安全停止;2-触发暂停;3-柔顺停止 - # "coeff": [100, 100, 100, 100, 100, 100], // 0-整机灵敏度百分比,1-单轴灵敏度百分比,2-单轴和整机灵敏度百分比 - # "coeff_level": 0, // 灵敏度等级:0-低,1-中,2-高 - # "compliance": 0, // 柔顺功能比例系数,[0-1] - # "enable": true, // 功能使能开关 - # "fallback_distance": 3, // 回退距离 - # "mode": 0, // 力传感器系数,0 整机 1 单轴 - # "percent": 100, // 0-200,整机灵敏度百分比 - # "percent_axis": [100, 100, 100, 100, 100, 100], // 0-200,单轴灵敏度百分比 - # "reduced_percent": 100, // 0-200,整机缩减模式灵敏度百分比 - # "reduced_percent_axis": [100, 100, 100, 100, 100, 100] // 0-200,单轴缩减模式灵敏度百分比 - # } - # """ - # return self.__get_data(currentframe().f_code.co_name, "collision.get_params") - # - # def set_collision_params(self, enable, mode, action, percent, **kwargs): # OK - # """ - # 设置碰撞检测相关参数 - # :param enable: 功能使能开关 - # :param mode: 力传感器系数,0 整机 1 单轴 - # :param action: 触发行为:1-安全停止;2-触发暂停;3-柔顺停止 - # :param percent: 0-200,整机灵敏度百分比 - # :return: - # """ - # data = self.get_collision_params - # keys = data.keys() - # kwargs.update({"enable": enable, "mode": mode, "action": action, "percent": percent}) - # for _ in keys: - # if _ in kwargs.keys(): - # data[_] = kwargs[_] - # self.execution("collision.set_params", data=data) - # - # def set_collision_state(self, collision_state: bool): # NG - # """ - # 开启或者关闭虚拟墙碰撞检测,测试该函数功能无效!!! - # :param collision_state: 碰撞检测的开关状态 - # :return: None - # """ - # self.execution("collision.set_state", collision_state=collision_state) - # - # @property - # def get_robot_state(self): # OK - # """ - # { - # "rc_state":"normal", # "fatal" 、"error"、"block"、"normal" - # "engine":"on", # "fatal" 、"error"、"GStop"、"EStop"、"on"、"off" - # "servo_mode":"position", # "torque"、"position" - # "operate": "auto", # "auto"、"manual" - # "task_space": "program", # "jog"、"drag"、"ready"、"load_identify"、"demo"、"rci"、"dynamic_identify"、"program"、"debug" - # "robot_action": "idle", # "idle"、"busy" - # "safety_mode": "collision" # "normal"、"collision"、"collaboration" - # } - # """ - # return self.__get_data(currentframe().f_code.co_name, "state.get_state") - # - # def set_controller_params(self, robot_time: str): # OK - # """ - # 设置控制器系统时间 - # :param robot_time: 系统时间,"2020-02-28 15:28:30" - # :return: None - # """ - # self.execution("controller.set_params", time=robot_time) - # - # @property - # def get_robot_params(self): # OK - # """ - # "alias": "", - # "auth_state": - # "controller_type": "XBC_XMATE", - # "controller_types": ["XBC_3", "XBC_5", "XBC_XMATE"], - # "disk_serial_number": "2338020401535", - # "mac_addr": "34:df:20:03:1b:45", - # "model":, - # "nic_list": ["enp1s0", "enp2s0"], - # "occupied_addr": "192.168.2.123:49269", - # "period": 0.002, - # "period_types": [0.001, 0.002, 0.003, 0.004], - # "robot_template": 10, - # "robot_type": "XMC12-R1300-W7G3B1C", - # "robot_types": ["XMC12-R1300-B7S3B0C", "XMC12-R1300-W7G3B1C", "XMC17_5-R1900-W7G3B1C", "XMC20-R1650-B7G3Z0C"], - # "security_type": "ROKAE_RSC", - # "security_types": ["ROKAE_MINI", "ROKAE_RSC"], - # "time": "2024-09-13 12:36:38", - # "version": "2.3.0.4" - # """ - # return self.__get_data(currentframe().f_code.co_name, "controller.get_params") - # - # def switch_tp_mode(self, mode: str): # OK - # """ - # 切换示教器模式 - # :param mode: with/without - # :return: None - # """ - # match mode: - # case "with": - # self.execution("state.set_tp_mode", tp_mode="with") - # case "without": - # self.execution("state.set_tp_mode", tp_mode="without") - # case _: - # clibs.insert_logdb("ERROR", "openapi", "hr: switch_tp_mode 参数错误 非法参数,只接受 with/without") - # - # @property - # def get_tp_mode(self): # OK - # """ - # 获取示教器连接状态 - # :return: - # { - # "tp_mode":"with" - # } - # """ - # return self.__get_data(currentframe().f_code.co_name, "state.get_tp_mode") - # - # @property - # def get_drag_params(self): # OK - # """ - # 获取拖动模式参数 - # :return: - # { - # "enable": true, - # "space": 0, - # "type": 0 - # } - # """ - # return self.__get_data(currentframe().f_code.co_name, "drag.get_params") - # - # def set_drag_params(self, enable: bool, space: int = 1, type: int = 2): # OK - # """ - # 设置拖动模式开关以及参数 - # :param enable: 是否启用拖动 - # :param space: 拖动空间 - 0 代表关节 1 代表笛卡尔 - # :param type: 拖动类型 - 0 只平移 1 只旋转 2 自由拖动 - # :return: None - # """ - # self.execution("drag.set_params", enable=enable, space=space, type=type) - # - # def set_safety_area_signal(self, signal: bool): # OK - # """ - # 设置安全区域信号控制使能开关 - # :param signal: True 打开 False 关闭 - # :return: None - # """ - # self.execution("safety.safety_area.signal_enable", protocol_flag=1, signal=signal) - # - # def set_safety_area_overall(self, enable: bool): # OK - # """ - # 设置安全区域整体控制使能开关 - # :param enable: True 打开 False 关闭 - # :return: None - # """ - # self.execution("safety.safety_area.overall_enable", protocol_flag=1, enable=enable) - # - # @property - # def get_safety_area_params(self): # OK - # """ - # 获取安全区所有的配置信息 - # :return: - # "g": { - # "safety_area_data": { - # "overall_enable": true, - # "safety_area_setting": [ - # { - # "box": { - # "Lx": 100.0, - # "Ly": 100.0, - # "Lz": 100.0, - # "direction": false, - # "ori": { - # "euler": { - # "a": 179.9963851353547, - # "b": -0.006653792532429416, - # "c": 179.9934560302729 - # }, - # "quaternion": { - # "q1": 0.0, - # "q2": 0.0, - # "q3": 0.0, - # "q4": 0.0 - # } - # }, - # "pos": { - # "x": 0.0, - # "y": 0.0, - # "z": 0.0 - # } - # }, - # "enable": false, - # "id": 0, - # "name": "region1", - # "plane": { - # "direction": true, - # "point": { - # "x": 0.0, - # "y": 0.0, - # "z": 0.0 - # }, - # "vector": { - # "x": 0.0, - # "y": 0.0, - # "z": 0.0 - # } - # }, - # "shape": 0, - # "shared_bind_di": "", - # "shared_bind_do": "", - # "sphere": { - # "ori": { - # "euler": { - # "a": 0.0, - # "b": 0.0, - # "c": 0.0 - # }, - # "quaternion": { - # "q1": 0.0, - # "q2": 0.0, - # "q3": 0.0, - # "q4": 0.0 - # } - # }, - # "pos": { - # "x": 0.0, - # "y": 0.0, - # "z": 0.0 - # }, - # "radius": 0.0 - # }, - # "state": true, - # "trigger": 0, - # "type": 0, - # "vertebral": { - # "high": 0.0, - # "ori": { - # "euler": { - # "a": 0.0, - # "b": 0.0, - # "c": 0.0 - # }, - # "quaternion": { - # "q1": 0.0, - # "q2": 0.0, - # "q3": 0.0, - # "q4": 0.0 - # } - # }, - # "pos": { - # "x": 0.0, - # "y": 0.0, - # "z": 0.0 - # }, - # "radius": 0.0 - # } - # }, - # ... // 剩余 9 个安全区域的配置信息 - # ], - # "signal_enable": true - # } - # } - # } - # """ - # return self.__get_data(currentframe().f_code.co_name, "safety_area_data", flag=1) - # - # def set_safety_area_enable(self, id: int, enable: bool): # OK - # """ - # 设置每个安全区域的开关 - # :param id: 安全区域开关,0-9 - # :param enable: True 打开,False 关闭 - # :return: None - # """ - # self.execution("safety.safety_area.safety_area_enable", protocol_flag=1, id=id, enable=enable) - # - # def set_safety_area_param(self, id: int, enable: bool, **kwargs): # OK - # """ - # 设定单独安全区的参数 - # :param id: 安全区 id - # :param enable: 是否开启 - # :param kwargs: 其他参数,参考 get_safety_area_params 的返回值形式 - # :return: None - # """ - # data = self.get_safety_area_params["g"]["safety_area_data"]["safety_area_setting"][id] - # keys = data.keys() - # kwargs.update({"id": id, "enable": enable}) - # for _ in keys: - # if _ in kwargs.keys(): - # data[_] = kwargs[_] - # self.execution("safety.safety_area.set_param", protocol_flag=1, data=data) - # self.execution("safety.safety_area.safety_area_enable", protocol_flag=1, id=id, enable=enable) - # - # @property - # def get_filtered_error_code(self): # OK - # """ - # 获取已设定的错误码过滤列表 - # :return: - # { - # "g": { - # "log_code.data": { - # "code_list": [ - # { - # "id": 100, - # "title": "DEMO\\u610f\\u5916\\u505c\\u6b62" - # }, - # { - # "id": 10000, - # "title": "HMI\\u8bf7\\u6c42\\u5305\\u89e3\\u6790\\u9519\\u8bef" - # }, - # { - # "id": 10002, - # "title": "\\u5feb\\u901f\\u8c03\\u6574\\u542f\\u52a8\\u5931\\u8d25" - # } - # ], - # "version": 1 - # } - # } - # } - # """ - # return self.__get_data(currentframe().f_code.co_name, "log_code.data", flag=1) - # - # def set_filtered_error_code(self, action: str, code_list: list): # OK - # """ - # 清空,增加,删除错误过滤码 - # :param action: 支持 add/remove/clear,当为 clear 时,code_list 可为任意列表 - # :param code_list: 需要添加/删除的过滤码列表 - # :return: None - # """ - # origin_code_list = self.get_filtered_error_code["g"]["log_code.data"]["code_list"] - # # [{"id": 10000, "title": "HMI请求包解析错误"}, {"id": 10002, "title": "快速调整启动失败"}] - # if action == "clear": - # code_list = [] - # elif action == "add": - # for error_code in code_list: - # for item in origin_code_list: - # if error_code == item["id"]: - # break - # else: - # origin_code_list.append({"id": error_code, "title": ""}) - # code_list = origin_code_list - # elif action == "remove": - # for error_code in code_list: - # for item in origin_code_list: - # if error_code == item["id"]: - # origin_code_list.remove(item) - # code_list = origin_code_list - # - # self.execution("log_code.data.code_list", protocol_flag=1, code_list=code_list) - # - # @staticmethod - # def __cannot_find_response(func_name, req_id): - # # 无法获取响应信息时,记录错误信息,并退出 - # clibs.insert_logdb("ERROR", "openapi", f"hr: [{func_name}] 无法找到 {req_id} 的响应信息,执行失败,退出...") - # exit() - # - # def __get_data(self, upper_func, command, flag=0, **kwargs): - # r_id = self.execution(command, protocol_flag=flag, **kwargs) - # res = self.get_from_id(r_id, flag=flag) - # if res is not None: - # return res - # else: - # self.__cannot_find_response(upper_func, r_id) + def switch_motor_state(self, state: str): # OK + """ + 切换上电/下电的状态 + :param state: on/off + :return: None + """ + match state: + case "on": + self.execution("state.switch_motor_on") + case "off": + self.execution("state.switch_motor_off") + case _: + clibs.insert_logdb("ERROR", "openapi", f"hr: switch_motor_state 参数错误 {state}: 非法参数,只接受 on/off") + + def switch_operation_mode(self, mode: str): # OK + """ + 切换自动/手动操作模式 + :param mode: auto/manual + :return: None + """ + match mode: + case "auto": + self.execution("state.switch_auto") + case "manual": + self.execution("state.switch_manual") + case _: + clibs.insert_logdb("ERROR", "openapi", "hr: switch_operation_mode 参数错误 非法参数,只接受 auto/manual") + + def reload_project(self, prj_name: str, tasks: list): # OK + """ + 重新加载指定工程 + :param prj_name: 工程名,也即 zip 文件的名字 + :param tasks: 要加载的任务列表 + :return: None + """ + prj_path = f"{prj_name}/_build/{prj_name}.prj" + self.execution("overview.reload", prj_path=prj_path, tasks=tasks) + + def set_project_auto_reload(self, prj_name: str): # OK + """ + 将指定工程设置为开机自动加载,也即默认工程 + :param prj_name: 工程名,也即 zip 文件的名字 + :return: None + """ + autoload_prj_path = f"{prj_name}/_build/{prj_name}.prj" + self.execution("overview.set_autoload", autoload_prj_path=autoload_prj_path) + + def pp_to_main(self, tasks: list): # OK + """ + 将指定的任务列表的指针,指向 main 函数 + :param tasks: 任务列表 + :return: None + """ + self.execution("rl_task.pp_to_main", tasks=tasks) + + def program_start(self, tasks: list): # OK + """ + 开始执行程序任务,必须是自动模式下执行 + :param tasks: 任务列表 + :return: None + """ + self.execution("rl_task.run", tasks=tasks) + + def program_stop(self, tasks: list): # OK + """ + 停止执行程序任务 + :param tasks: 人物列表 + :return: None + """ + self.execution("rl_task.stop", tasks=tasks) + + def set_program_loop_speed(self, loop_mode: bool = True, override: float = 0.5): # OK + """ + :param loop_mode: True为循环模式,False为单次模式 + :param override: HMI 左下方的速度滑块,取值范围 [0, 1] + :return: None + """ + self.execution("rl_task.set_run_params", loop_mode=loop_mode, override=override) + + def clear_alarm(self): # OK + """ + 清除伺服告警 + :return: None + """ + self.execution("servo.clear_alarm") + + def reboot_robot(self): # OK + """ + 重启控制器 + :return: None + """ + self.execution("controller.reboot") + clibs.insert_logdb("INFO", "openapi", f"hr: 控制器重启中,重连预计需要等待 100s 左右...") + ts = time() + time.sleep(30) + while True: + time.sleep(5) + te = time() + if te - ts > 180: + self.__silence = False + self.__sth_wrong("3min 内未能完成重新连接,需要查看后台控制器是否正常启动,或者 ip/port 是否正确") + break + for _ in range(3): + if not self.__is_connected: + break + time.sleep(2) + else: + clibs.insert_logdb("INFO", "openapi", "hr: HMI 重新连接成功...") + break + + def reload_io(self): + """ + 触发控制器重新加载 IO 设备列表 + :return: None + """ + self.execution("io_device.load_cfg") + + @property + def get_quickturn_pos(self): # OK + """ + 获取机器人的home位姿、拖动位姿和发货位姿,轴关节角度,end_posture 取值如下: + 0 法兰平面与地面平行 + 1 工具坐标系X轴与地面垂直,正向朝下 + 2 工具坐标系X轴与地面垂直,正向朝上 + 3 工具坐标系Y轴与地面垂直,正向朝下 + 4 工具坐标系Y轴与地面垂直,正向朝上 + 5 工具坐标系Z轴与地面垂直,正向朝下 + 6 工具坐标系Z轴与地面垂直,正向朝上 + :return: as below + { + "enable_home": false, // 是否开启 home 点快速调整 + "enable_drag": false, // 是否开启拖动位姿点快速调整 + "enable_transport": false, // 是否开启发货位姿点快速调整 + "joint_home": [0.0,0.0,0.0,0.0,0.0,0.0,0.0], // home 位姿的关节角度 + "joint_drag": [0.0,0.0,0.0,0.0,0.0,0.0,0.0], // 拖动位姿的关节角度 + "joint_transport": [0.0,0.0,0.0,0.0,0.0,0.0,0.0], // 发货位姿的关节角度 + "end_posture":0, // 末端姿态的调整方式,取值 0-6 + "home_error_range":[0.0,0.0,0.0,0.0,0.0,0.0,0.0] // home点误差范围 + } + """ + return self.__get_data(currentframe().f_code.co_name, "move.get_quickturn_pos") + + def set_quickturn_pos(self, enable_home: bool = False, enable_drag: bool = False, enable_transport: bool = False, end_posture: int = 0): # OK + """ + 设置机器人的home位姿、拖动位姿、发货位姿,轴关节角度,Home点误差范围,详见上一个 get_quickturn_pos 功能实现 + :param enable_home: 是否开启 home 点快速调整 + :param enable_drag: 是否开启拖动位姿点快速调整 + :param enable_transport:是否开启发货位姿点快速调整 + :param end_posture: 末端姿态的调整方式,取值 0-6,详见 get_quickturn_pos 注释 + :return: None + """ + self.execution("move.set_quickturn_pos", enable_home=enable_home, enable_drag=enable_drag, enable_transport=enable_transport, end_posture=end_posture) + + def move2quickturn(self, name: str): # OK + """ + 运动到指定的快速调整位姿 + :param name: 指定快速调整的名称,home/drag/transport + :return: None + """ + self.execution("move.quick_turn", name=name) + + def stop_move(self, stoptype=0): # OK + """ + 停止运动 + TS_READY | TS_JOG | TS_LOADIDENTIFY | TS_DYNAMICIDENTIFY | TS_DRAG | TS_PROGRAM | TS_DEMO | TS_RCI | TS_DEBUG | TS_FRICTIONIDENTIFY + :param stoptype: 对应控制器的任务空间类型TaskSpace的枚举值,0-7 + :return: None + """ + self.execution("move.stop", stoptype=stoptype) + + @property + def get_jog_params(self): # OK + """ + 获取JOG的参数 + 世界坐标系 WORLD_COORDINATE 0 + 法兰盘坐标系 FLANGE_COORDINATE 1 + 基坐标系 BASE_COORDINATE 2 + 工具坐标系 TOOL_COORDINATE 3 + 工件坐标系 FRAME_COORDINATE 4 + 关节空间 JOINT_SPACE 5 + :return: + { + "step": 1000 [1000-连续] [10/1/0.1/0.001-点动] + "override": 0.2 速度比率 + "space": 5 JOG的空间 + } + """ + return self.__get_data(currentframe().f_code.co_name, "jog.get_params") + + def set_jog_params(self, step, override, space): # OK + """ + 设置JOG的参数,包含步长,空间,速度倍率 + :param step: [1000-连续] [10/1/0.1/0.001-点动] + :param override: 速度比率 + :param space: JOG的空间 + :return: None + """ + self.execution("jog.set_params", step=step, override=override, space=space) + + def start_jog(self, index: int, direction: bool = False, is_ext: bool = False): # OK + """ + 开始 JOG 运动 + :param index: 0-6,若选轴空间,则 0-6 对应 1-7 轴,若选笛卡尔空间,则 0-6 对应 xyzabc elb + :param direction: True 正方向,False 反方向 + :param is_ext: 是否是外部轴 jog + :return: None + """ + self.execution("jog.start", index=index, direction=direction, is_ext=is_ext) + + @property + def get_socket_params(self): # OK + """ + 获取socket参数 + :return: + { + "auto_connect": true, // True 开机启动,False 不开机启动 + "disconnection_detection_time": 10, // 链接断开检测周期(s) + "disconnection_triggering_behavior": 0, // 断开连接触发行为 0无动作 1暂停程序 2暂停并下电 + "enable": true, // True 开启或者 False 关闭 + "ip": "", // 仅限于客户端,用于指定服务端 IP;当作为服务端时,该参数设置为空字符串,否则会报错!!! + "name": "name", // 连接名称 + "port": "8080", // 连接端口 + "reconnect_flag": true, // True 自动重连,False 不自动重连 + "suffix": "\r", // 指定发送分隔符 + "type": 1 // 连接类型 0 client | 1 server + } + """ + return self.__get_data(currentframe().f_code.co_name, "socket.get_params") + + def set_socket_params(self, enable: bool, port: str, suffix: str, type: int = 1, **kwargs): # OK + """ + 设置 socket 参数,一般作为服务器使用 + :param enable: True 开启或者 False 关闭 + :param port: 连接端口 + :param suffix: 指定发送分隔符 + :param type: 0 client | 1 server + :return: None + """ + data = self.get_socket_params + keys = data.keys() + kwargs.update({"enable": enable, "port": port, "suffix": suffix, "type": type}) + for _ in keys: + if _ in kwargs.keys(): + data[_] = kwargs[_] + self.execution("socket.set_params", data=data) + + @property + def get_diagnosis_params(self, version="1.4.1"): # OK + """ + 获取诊断功能开启状态,以及相应其他信息 + :param version: 指定诊断工具版本 + :return: + { + "delay_motion": false, // - + "display_open": false, // 诊断显示功能开启状态 + "ecat_diagnosis_state": false, // - + "overrun": false, // 是否开启实时线程超时监控上报 + "pdo_params": [...], // 指定版本支持的所有曲线信息 + "state": true, // 诊断功能的开启状态 + "turn_area": false // 转弯区是否上报 + } + """ + return self.__get_data(currentframe().f_code.co_name, "diagnosis.get_params", version=version) + + def set_diagnosis_params(self, display_pdo_params: list, frequency: int = 50, version: str = "1.4.1"): # OK + """ + 设置诊断功能显示参数 [{"name": "hw_joint_vel_feedback", "channel": 0}, ] + :param display_pdo_params: 指定要采集的曲线名称,具体可通过 get_diagnosis_params 函数功能获取所有目前已支持的曲线 + :param frequency: 采样频率,默认 50ms + :param version: xDiagnose的版本号 + :return: None + """ + self.execution("diagnosis.set_params", display_pdo_params=display_pdo_params, frequency=frequency, version=version) + + def open_diagnosis(self, open: bool, display_open: bool, overrun: bool = False, turn_area: bool = False, delay_motion: bool = False): # OK + """ + 打开或者关闭诊断曲线,并定义其他功能的开关(调试相关功能,比如是否开启线程超时监控和上报,转弯区以及运动延迟等) + :param open: 诊断功能,控制HMI->日志->诊断设置->私服诊断开关,一般设置成 True + :param display_open: 诊断显示功能,指的是在线诊断插件中的打开 switch 的状态,需要诊断数据的情况,设置成 True + :param overrun: 实时线程超时监控上报 + :param turn_area: 转弯区上报 + :param delay_motion: 延迟运动 + :return: None + """ + self.execution("diagnosis.open", open=open, display_open=display_open, overrun=overrun, turn_area=turn_area, delay_motion=delay_motion) + + def save_diagnosis(self, save: bool = True): # OK + """ + 保存诊断数据,也就是主动写诊断动作,HMI日志->诊断设置->保存诊断数据 + :param save: 保存数据开关 + :return: None + """ + self.execution("diagnosis.save", save=save) + + @property + def qurry_system_io_configuration(self): # OK + """ + 系统IO配置的查询协议,trigger 参数取值参照如下: + FLANKS 0, //边缘触发 + POS_FLANK 1, //上升沿 + NEG_FLANK 2, //下降沿 + HIGH_LEVEL 3, //高电平 + LOW_LEVEL 4 //低电平 + :return: + { + "input_system_io": { + "motor_on": { + "signal":"DI0_0", + "trigger":1 + }, + "motor_off": { + "signal":"DI0_0", + "trigger":2 + } + }, + "output_system_io": { + "sta_motor_on": { + "signal":"DO0_0" + }, + "sta_robot_running": { + "signal":"DO0_1" + } + } + } + """ + return self.__get_data(currentframe().f_code.co_name, "system_io.query_configuration") + + @property + def qurry_system_io_event_configuration(self): # OK + """ + 查询当前系统支持的系统IO事件列表,包括事件key、名称、支持的触发方式等配置 + :return: + { + "input_system_event": [ + { + "key": "ctrl_motor_on", + "name": "上电", + "trigger_types": [ + 1, + 2 + ] + }, + { + "key": "ctrl_motor_off", + "name": "下电", + "trigger_types": [ + 1, + 2 + ] + } + ], + "output_system_event": [ + { + "key": "sta_motor_on", + "name": "上下电状态" + }, + { + "key": "sta_program", + "name": "运行状态" + } + ], + "input_mutex_event": [ + { + "key0": "ctrl_motor_on", + "key1": "ctrl_motor_off" + }, + { + "key0": "ctrl_switch_auto", + "key1": "ctrl_switch_manu" + } + ] + } + """ + return self.__get_data(currentframe().f_code.co_name, "system_io.query_configuration") + + def update_system_io_configuration(self, i_funcs: list, o_funcs: list, i_signals: list, o_signals: list, trig_types: list): # OK + """ + 配置系统 IO + :param i_funcs: 输入,只写功能码列表 + :param o_funcs: 输出,只读功能码列表 + :param i_signals: DI 信号列表 + :param o_signals: DO 信号列表 + :param trig_types: 触发条件列表,可参考 qurry_system_io_configuration 中的触发条件 + :return: None + """ + input_system_io, output_system_io = {}, {} + for i_func in i_funcs: + _index = i_funcs.index(i_func) + input_system_io[i_func] = {"signal": i_signals[_index], "trigger": trig_types[_index]} + for o_func in o_funcs: + _index = o_funcs.index(o_func) + output_system_io[o_func] = {"signal": o_signals[_index]} + self.execution("system_io.update_configuration", input_system_io=input_system_io, output_system_io=output_system_io) + + @property + def get_fieldbus_device_params(self): # OK + """ + 获取的是 HMI通讯->总线设备列表的信息,以及开关状态 + :return: + { + "device_list": [ + { + "device_name": "modbus_1", + "enable": true + }, { + "device_name": "modbus_2", + "enable": false + } + ] + } + """ + return self.__get_data(currentframe().f_code.co_name, "fieldbus_device.get_params") + + def set_fieldbus_device_params(self, device_name: str, enable: bool): # OK + """ + 定义开关设备的协议,一次只能打开一个设备 + :param device_name: 设备列表中的名称 + :param enable: 是否开启,这里操作的是 HMI通信->IO设备里面的开关状态 + :return: None + """ + self.execution("fieldbus_device.set_params", device_name=device_name, enable=enable) + + def reload_fieldbus(self): # OK + """ + 触发控制器重新加载总线设备 + :return: None + """ + self.execution("fieldbus_device.load_cfg") + + @property + def get_modbus_params(self): # OK + """ + 获取modbus参数 + :return: + { + "connect_state": true, + "enable_master": false, + "enable_slave": false, + "ip": "192.168.0.160", + "is_convert": true, + "port": 502, + "slave_id": 1 + } + """ + return self.__get_data(currentframe().f_code.co_name, "modbus.get_params") + + def set_modbus_params(self, enable_slave: bool, ip: str, port: int, slave_id: int, enable_master: bool): # OK + """ + 设置modbus参数,相当于新建 + :param enable_slave: Modbus从站是否自动开启 + :param ip: ip 地址 + :param port: 端口 + :param slave_id: 从站 ID + :param enable_master: Modbus主站是否自动开启 + :return: + """ + self.execution("modbus.set_params", enable_slave=enable_slave, ip=ip, port=port, slave_id=slave_id, enable_master=enable_master) + + def reload_registers(self): # OK + """ + 触发控制器重新加载寄存器列表 + :return: None + """ + self.execution("modbus.load_cfg") + + def get_modbus_values(self, mode: str = "all"): # OK + """ + 用于获取 modbus 寄存器变量值的更新信息,展示在状态监控界面 + :param mode: all/change + :return: + """ + return self.__get_data(currentframe().f_code.co_name, "modbus.get_values", mode=mode) + + @property + def get_soft_limit_params(self): # OK + """ + 获取软限位参数 + :return: + { + "enable":true + "upper":[0,0,0,0,0,0,0], + "lower":[0,0,0,0,0,0,0], + "reduced_upper":[0,0,0,0,0,0,0], + "reduced_lower":[0,0,0,0,0,0,0] + } + """ + return self.__get_data(currentframe().f_code.co_name, "soft_limit.get_params") + + def set_soft_limit_params(self, **kwargs): # OK + """ + 设定软限位参数 enable: bool, upper: list, lower: list, reduced_upper: list, reduced_lower: list + :enable: 是否启用软限位 + :upper: 软限位上限 + :lower: 软限位下限 + :reduced_upper: 缩减模式软限位上限 + :reduced_lower: 缩减模式软限位下限 + :return: None + """ + data = self.get_soft_limit_params + keys = data.keys() + for _ in keys: + if _ in kwargs.keys(): + data[_] = kwargs[_] + self.execution("soft_limit.set_params", data=data) + + @property + def get_device_params(self): # OK + """ + 获取设备信息 + :return: + """ + return self.__get_data(currentframe().f_code.co_name, "device.get_params") + + @property + def get_cart_pos(self): # OK + """ + 获取机器人的当前位姿:包括轴关节角度,笛卡尔关节角度,四元数,欧拉角(臂角) + :return: + { + "joint":[0.0,0.0,0.0,0.0,0.0,0.0], + "position":[0.0,0.0,0.0,0.0,0.0,0.0], + "euler":[0.0,0.0,0.0], + "quaternion"[0.0,0.0,0.0,0.0], + "elb":0.0, // 可缺省 + "ext_joint":[0.0,0.0,0.0,0.0,0.0] + } + """ + return self.__get_data(currentframe().f_code.co_name, "move.get_pos") + + @property + def get_joint_pos(self): # OK + """ + 获取机器人的当前关节角度:包括内部轴和外部轴 + :return: + { + "inner_pos": [0,0,0,0,0,0,0], + "extern_pos": [0,0,0,0,0,0,0] + } + """ + return self.__get_data(currentframe().f_code.co_name, "move.get_joint_pos") + + @property + def get_monitor_cfg(self): # OK + """ + 获取机器人的监控配置参数,RefCoordinateType 类型数据,表示当前控制器位置监测的相对坐标系 + 基坐标系 REF_COORDINATE_BASE 0 + 世界坐标系 REF_COORDINATE_WORLD 1 + 工件坐标系 REF_COORDINATE_WOBJ 2 + :return: + { + "ref_coordinate": 0 + } + """ + return self.__get_data(currentframe().f_code.co_name, "move.get_monitor_cfg") + + def set_monitor_cfg(self, ref_coordinate): # OK + """ + 设置机器人的监控配置参数 + :ref_coordinate: RefCoordinateType类型数据,用来设置当前控制器位置监测的相对坐标系 + :return: None + """ + self.execution("move.set_monitor_cfg", ref_coordinate=ref_coordinate) + + @property + def get_move_params(self): # OK + """ + 获取机器人的运动参数:包括减速比、耦合比、最大速度、加速度、加加速度、acc ramp time、规划步长等信息 + :return: + { + "MOTION": { + "ACC_RAMPTIME_JOG": 0.5, + "ACC_RAMPTIME_STOP": 0.5, + "DEFAULT_ACC_PARAMS": [1.0, 0.5], + "JERK_LIMIT_CART": 0, + "JERK_LIMIT_JOINT": 0, + "JERK_LIMIT_ROT": 0, + "JOINT_MAX_ACC": [500, 500, 1000, 1000, 1000], + "JOINT_MAX_JERK": [2000, 2000, 2000, 4000, 4000, 4000], + "JOINT_MAX_SPEED": [120.0, 120.0, 180.0, 180.0, 180.0, 180.0], + "MAX_ACC_PARAMS": [1.0, 1], + "MIN_ACC_PARAMS": [0.3, 0.05], + "TCP_MAX_ACC": 5000, + "TCP_MAX_JERK": 10000, + "TCP_MAX_SPEED": 1000, + "TCP_ROTATE_MAX_ACC": 1800, + "TCP_ROTATE_MAX_JERK": 3600, + "TCP_ROTATE_MAX_SPEED": 180, + "VEL_SMOOTH_FACTOR": 1.0, + "VEL_SMOOTH_FACTOR_RANGE": [1.0, 10.0] + } + } + """ + return self.__get_data(currentframe().f_code.co_name, "move.get_params") + + def set_move_params(self, **kwargs): # OK + """ + 设置机器人的运动参数:轴最大速度、轴最大加加速度、速度、加加速度、加速度、加加速度、acc ramp time、规划步长等信息 + 可选参数:参考 get_move_params 函数返回值 MOTION 里面的选项 + :return: None + """ + data = self.get_move_params["MOTION"] + print(f"res = {data}") + keys = data.keys() + for _ in keys: + if _ in kwargs.keys(): + data[_] = kwargs[_] + self.execution("move.set_params", data=data) + + @property + def get_quick_stop_distance(self): # OK + """ + 获取机器人 search 指令最大停止距离 + :return: + { + "distance":2.0 + } + """ + return self.__get_data(currentframe().f_code.co_name, "move.get_quickstop_distance") + + def set_quick_stop_distance(self, distance: float): # OK + """ + 设置机器人 search 指令最大停止距离 + :param distance: 停止距离,单位 mm + :return: None + """ + self.execution("move.set_quickstop_distance", distance=distance) + + @property + def get_collision_params(self): # OK + """ + 获取碰撞检测相关参数 + :return: + { + "action": 1, // 触发行为:1-安全停止;2-触发暂停;3-柔顺停止 + "coeff": [100, 100, 100, 100, 100, 100], // 0-整机灵敏度百分比,1-单轴灵敏度百分比,2-单轴和整机灵敏度百分比 + "coeff_level": 0, // 灵敏度等级:0-低,1-中,2-高 + "compliance": 0, // 柔顺功能比例系数,[0-1] + "enable": true, // 功能使能开关 + "fallback_distance": 3, // 回退距离 + "mode": 0, // 力传感器系数,0 整机 1 单轴 + "percent": 100, // 0-200,整机灵敏度百分比 + "percent_axis": [100, 100, 100, 100, 100, 100], // 0-200,单轴灵敏度百分比 + "reduced_percent": 100, // 0-200,整机缩减模式灵敏度百分比 + "reduced_percent_axis": [100, 100, 100, 100, 100, 100] // 0-200,单轴缩减模式灵敏度百分比 + } + """ + return self.__get_data(currentframe().f_code.co_name, "collision.get_params") + + def set_collision_params(self, enable, mode, action, percent, **kwargs): # OK + """ + 设置碰撞检测相关参数 + :param enable: 功能使能开关 + :param mode: 力传感器系数,0 整机 1 单轴 + :param action: 触发行为:1-安全停止;2-触发暂停;3-柔顺停止 + :param percent: 0-200,整机灵敏度百分比 + :return: + """ + data = self.get_collision_params + keys = data.keys() + kwargs.update({"enable": enable, "mode": mode, "action": action, "percent": percent}) + for _ in keys: + if _ in kwargs.keys(): + data[_] = kwargs[_] + self.execution("collision.set_params", data=data) + + def set_collision_state(self, collision_state: bool): # NG + """ + 开启或者关闭虚拟墙碰撞检测,测试该函数功能无效!!! + :param collision_state: 碰撞检测的开关状态 + :return: None + """ + self.execution("collision.set_state", collision_state=collision_state) + + @property + def get_robot_state(self): # OK + """ + { + "rc_state":"normal", # "fatal" 、"error"、"block"、"normal" + "engine":"on", # "fatal" 、"error"、"GStop"、"EStop"、"on"、"off" + "servo_mode":"position", # "torque"、"position" + "operate": "auto", # "auto"、"manual" + "task_space": "program", # "jog"、"drag"、"ready"、"load_identify"、"demo"、"rci"、"dynamic_identify"、"program"、"debug" + "robot_action": "idle", # "idle"、"busy" + "safety_mode": "collision" # "normal"、"collision"、"collaboration" + } + """ + return self.__get_data(currentframe().f_code.co_name, "state.get_state") + + def set_controller_params(self, robot_time: str): # OK + """ + 设置控制器系统时间 + :param robot_time: 系统时间,"2020-02-28 15:28:30" + :return: None + """ + self.execution("controller.set_params", time=robot_time) + + @property + def get_robot_params(self): # OK + """ + "alias": "", + "auth_state": + "controller_type": "XBC_XMATE", + "controller_types": ["XBC_3", "XBC_5", "XBC_XMATE"], + "disk_serial_number": "2338020401535", + "mac_addr": "34:df:20:03:1b:45", + "model":, + "nic_list": ["enp1s0", "enp2s0"], + "occupied_addr": "192.168.2.123:49269", + "period": 0.002, + "period_types": [0.001, 0.002, 0.003, 0.004], + "robot_template": 10, + "robot_type": "XMC12-R1300-W7G3B1C", + "robot_types": ["XMC12-R1300-B7S3B0C", "XMC12-R1300-W7G3B1C", "XMC17_5-R1900-W7G3B1C", "XMC20-R1650-B7G3Z0C"], + "security_type": "ROKAE_RSC", + "security_types": ["ROKAE_MINI", "ROKAE_RSC"], + "time": "2024-09-13 12:36:38", + "version": "2.3.0.4" + """ + return self.__get_data(currentframe().f_code.co_name, "controller.get_params") + + def switch_tp_mode(self, mode: str): # OK + """ + 切换示教器模式 + :param mode: with/without + :return: None + """ + match mode: + case "with": + self.execution("state.set_tp_mode", tp_mode="with") + case "without": + self.execution("state.set_tp_mode", tp_mode="without") + case _: + clibs.insert_logdb("ERROR", "openapi", "hr: switch_tp_mode 参数错误 非法参数,只接受 with/without") + + @property + def get_tp_mode(self): # OK + """ + 获取示教器连接状态 + :return: + { + "tp_mode":"with" + } + """ + return self.__get_data(currentframe().f_code.co_name, "state.get_tp_mode") + + @property + def get_drag_params(self): # OK + """ + 获取拖动模式参数 + :return: + { + "enable": true, + "space": 0, + "type": 0 + } + """ + return self.__get_data(currentframe().f_code.co_name, "drag.get_params") + + def set_drag_params(self, enable: bool, space: int = 1, type: int = 2): # OK + """ + 设置拖动模式开关以及参数 + :param enable: 是否启用拖动 + :param space: 拖动空间 - 0 代表关节 1 代表笛卡尔 + :param type: 拖动类型 - 0 只平移 1 只旋转 2 自由拖动 + :return: None + """ + self.execution("drag.set_params", enable=enable, space=space, type=type) + + def set_safety_area_signal(self, signal: bool): # OK + """ + 设置安全区域信号控制使能开关 + :param signal: True 打开 False 关闭 + :return: None + """ + self.execution("safety.safety_area.signal_enable", protocol_flag=1, signal=signal) + + def set_safety_area_overall(self, enable: bool): # OK + """ + 设置安全区域整体控制使能开关 + :param enable: True 打开 False 关闭 + :return: None + """ + self.execution("safety.safety_area.overall_enable", protocol_flag=1, enable=enable) + + @property + def get_safety_area_params(self): # OK + """ + 获取安全区所有的配置信息 + :return: + "g": { + "safety_area_data": { + "overall_enable": true, + "safety_area_setting": [ + { + "box": { + "Lx": 100.0, + "Ly": 100.0, + "Lz": 100.0, + "direction": false, + "ori": { + "euler": { + "a": 179.9963851353547, + "b": -0.006653792532429416, + "c": 179.9934560302729 + }, + "quaternion": { + "q1": 0.0, + "q2": 0.0, + "q3": 0.0, + "q4": 0.0 + } + }, + "pos": { + "x": 0.0, + "y": 0.0, + "z": 0.0 + } + }, + "enable": false, + "id": 0, + "name": "region1", + "plane": { + "direction": true, + "point": { + "x": 0.0, + "y": 0.0, + "z": 0.0 + }, + "vector": { + "x": 0.0, + "y": 0.0, + "z": 0.0 + } + }, + "shape": 0, + "shared_bind_di": "", + "shared_bind_do": "", + "sphere": { + "ori": { + "euler": { + "a": 0.0, + "b": 0.0, + "c": 0.0 + }, + "quaternion": { + "q1": 0.0, + "q2": 0.0, + "q3": 0.0, + "q4": 0.0 + } + }, + "pos": { + "x": 0.0, + "y": 0.0, + "z": 0.0 + }, + "radius": 0.0 + }, + "state": true, + "trigger": 0, + "type": 0, + "vertebral": { + "high": 0.0, + "ori": { + "euler": { + "a": 0.0, + "b": 0.0, + "c": 0.0 + }, + "quaternion": { + "q1": 0.0, + "q2": 0.0, + "q3": 0.0, + "q4": 0.0 + } + }, + "pos": { + "x": 0.0, + "y": 0.0, + "z": 0.0 + }, + "radius": 0.0 + } + }, + ... // 剩余 9 个安全区域的配置信息 + ], + "signal_enable": true + } + } + } + """ + return self.__get_data(currentframe().f_code.co_name, "safety_area_data", flag=1) + + def set_safety_area_enable(self, id: int, enable: bool): # OK + """ + 设置每个安全区域的开关 + :param id: 安全区域开关,0-9 + :param enable: True 打开,False 关闭 + :return: None + """ + self.execution("safety.safety_area.safety_area_enable", protocol_flag=1, id=id, enable=enable) + + def set_safety_area_param(self, id: int, enable: bool, **kwargs): # OK + """ + 设定单独安全区的参数 + :param id: 安全区 id + :param enable: 是否开启 + :param kwargs: 其他参数,参考 get_safety_area_params 的返回值形式 + :return: None + """ + data = self.get_safety_area_params["g"]["safety_area_data"]["safety_area_setting"][id] + keys = data.keys() + kwargs.update({"id": id, "enable": enable}) + for _ in keys: + if _ in kwargs.keys(): + data[_] = kwargs[_] + self.execution("safety.safety_area.set_param", protocol_flag=1, data=data) + self.execution("safety.safety_area.safety_area_enable", protocol_flag=1, id=id, enable=enable) + + @property + def get_filtered_error_code(self): # OK + """ + 获取已设定的错误码过滤列表 + :return: + { + "g": { + "log_code.data": { + "code_list": [ + { + "id": 100, + "title": "DEMO\\u610f\\u5916\\u505c\\u6b62" + }, + { + "id": 10000, + "title": "HMI\\u8bf7\\u6c42\\u5305\\u89e3\\u6790\\u9519\\u8bef" + }, + { + "id": 10002, + "title": "\\u5feb\\u901f\\u8c03\\u6574\\u542f\\u52a8\\u5931\\u8d25" + } + ], + "version": 1 + } + } + } + """ + return self.__get_data(currentframe().f_code.co_name, "log_code.data", flag=1) + + def set_filtered_error_code(self, action: str, code_list: list): # OK + """ + 清空,增加,删除错误过滤码 + :param action: 支持 add/remove/clear,当为 clear 时,code_list 可为任意列表 + :param code_list: 需要添加/删除的过滤码列表 + :return: None + """ + origin_code_list = self.get_filtered_error_code["g"]["log_code.data"]["code_list"] + # [{"id": 10000, "title": "HMI请求包解析错误"}, {"id": 10002, "title": "快速调整启动失败"}] + if action == "clear": + code_list = [] + elif action == "add": + for error_code in code_list: + for item in origin_code_list: + if error_code == item["id"]: + break + else: + origin_code_list.append({"id": error_code, "title": ""}) + code_list = origin_code_list + elif action == "remove": + for error_code in code_list: + for item in origin_code_list: + if error_code == item["id"]: + origin_code_list.remove(item) + code_list = origin_code_list + + self.execution("log_code.data.code_list", protocol_flag=1, code_list=code_list) + + @staticmethod + def __cannot_find_response(func_name, req_id): + # 无法获取响应信息时,记录错误信息,并退出 + clibs.insert_logdb("ERROR", "openapi", f"hr: [{func_name}] 无法找到 {req_id} 的响应信息,执行失败,退出...") + exit() + + def __get_data(self, upper_func, command, flag=0, **kwargs): + msg_id, state = self.execution(command, protocol_flag=flag, **kwargs) + records = clibs.c_hr.get_from_id(msg_id, state) + for record in records: + if "请求发送成功" not in record[0]: + data = eval(record[0])["data"] + return data + # if res is not None: + # return res + # else: + # self.__cannot_find_response(upper_func, msg_id) # =================================== ↑↑↑ specific functions ↑↑↑ =================================== class ExternalCommunication(object): - def __init__(self): + def __init__(self, ip, port): self.__c = None + self.ip = ip + self.port = port self.suffix = "\r" self.socket_client() self.exec_desc = " :--: 返回 true 表示执行成功,false 失败" @@ -1880,7 +1882,7 @@ class ExternalCommunication(object): def socket_client(self): self.__c = socket.socket(socket.AF_INET, socket.SOCK_STREAM) try: - self.__c.connect((clibs.ip_addr, clibs.external_port)) + self.__c.connect((self.ip, self.port)) clibs.insert_logdb("INFO", "openapi", f"ec: 外部通信连接成功...") return self.__c except Exception as Err: diff --git a/code/data_process/brake.py b/code/data_process/brake.py index 96462b0..8d9f5ef 100644 --- a/code/data_process/brake.py +++ b/code/data_process/brake.py @@ -1,13 +1,14 @@ -import openpyxl +import json import os.path import time import pandas import threading +import openpyxl import re from common import clibs -def check_files(path, rawdata_dirs, result_files, w2t): +def check_files(rawdata_dirs, result_files, w2t): msg_wrong = "需要有四个文件和若干个数据文件夹,可参考如下确认:\n" msg_wrong += "1. reach33_XXXXXXX.xlsx\n2. reach66_XXXXXXX.xlsx\n3. reach100_XXXXXXX.xlsx\n4. *.cfg\n" msg_wrong += "- reach33_load33_speed33\nreach33_load33_speed66\n......\nreach100_load100_speed66\nreach100_load100_speed100\n" @@ -33,8 +34,10 @@ def check_files(path, rawdata_dirs, result_files, w2t): reach_s = ['reach33', 'reach66', 'reach100'] load_s = ['load33', 'load66', 'load100'] speed_s = ['speed33', 'speed66', 'speed100'] + prefix = [] for rawdata_dir in rawdata_dirs: components = rawdata_dir.split("/")[-1].split('_') # reach_load_speed + prefix.append(components[0]) if components[0] not in reach_s or components[1] not in load_s or components[2] not in speed_s: msg = f"报错信息:数据目录 {rawdata_dir} 命名不合规,请参考如下形式\n" msg += "命名规则:reachAA_loadBB_speedCC,AA/BB/CC 指的是臂展/负载/速度的比例\n" @@ -47,161 +50,139 @@ def check_files(path, rawdata_dirs, result_files, w2t): w2t(msg, "red", "WrongDataFile") for rawdata_file in rawdata_files: if not rawdata_file.endswith(".data"): - msg = f"数据文件 {rawdata_file} 后缀错误,每个数据目录下有且只能有三个以 .data 为后缀的数据文件" + msg = f"数据文件 {rawdata_file} 后缀错误,每个数据目录下有且只能有三个以 .data 为后缀的数据文件\n" w2t(msg, "red", "WrongDataFile") - w2t("数据目录合规性检查结束,未发现问题......") + result_files = [] + for _ in [reach33_file, reach66_file, reach100_file]: + if _.split("/")[-1].split("_")[0] in set(prefix): + result_files.append(_) + + w2t("数据目录合规性检查结束,未发现问题......\n") + return config_file, result_files -def get_configs(configfile, w2t): - axis = configfile.split('\\')[-2][-1] - if axis not in ['1', '2', '3']: - w2t("被处理的根文件夹命名必须是 [Jj][123] 的格式", 0, 9, 'red') - else: - axis = int(axis) +def get_configs(config_file, w2t): + try: + with open(config_file, mode="r", encoding="utf-8") as f_config: + configs = json.load(f_config) + except Exception as Err: + clibs.insert_logdb("ERROR", "current", f"get_config: 无法打开 {config_file},获取配置文件参数错误 {Err}") + w2t(f"无法打开 {config_file}", color="red", desc="OpenFileError") - _wb = load_workbook(configfile, read_only=True) - _ws = _wb['Target'] - rr = float(_ws.cell(row=2, column=axis + 1).value) - av = float(_ws.cell(row=3, column=axis + 1).value) + p_dir = config_file.split('/')[-2] + if not re.match("^[jJ][123]$", p_dir): + w2t("被处理的根文件夹命名必须是 [Jj][123] 的格式", "red", "DirNameError") + axis = int(p_dir[-1]) + + rrs = [abs(_) for _ in configs["TRANSMISSION"]["REDUCTION_RATIO_NUMERATOR"]] # 减速比,rr for reduction ratio + avs = configs["MOTION"]["JOINT_MAX_SPEED"] + rr = rrs[axis-1] + av = avs[axis-1] return av, rr def now_doing_msg(docs, flag, w2t): - # 功能:输出正在处理的文件或目录 - # 参数:文件或目录,start 或 done 标识 - # 返回值:- - now = strftime('%Y-%m-%d %H:%M:%S', localtime(time())) - file_type = 'file' if isfile(docs) else 'dir' + now = time.strftime('%Y-%m-%d %H:%M:%S', time.localtime(time.time())) + file_type = 'file' if os.path.isfile(docs) else 'dir' if flag == 'start' and file_type == 'dir': - w2t(f"[{now}] 正在处理目录 {docs} 中的数据......") + w2t(f"[{now}] 正在处理目录 {docs} 中的数据......\n") elif flag == 'start' and file_type == 'file': - w2t(f"[{now}] 正在处理文件 {docs} 中的数据......") + w2t(f"[{now}] 正在处理文件 {docs} 中的数据......\n") elif flag == 'done' and file_type == 'dir': - w2t(f"[{now}] 目录 {docs} 数据文件已处理完毕") + w2t(f"[{now}] 目录 {docs} 数据文件已处理完毕\n") elif flag == 'done' and file_type == 'file': - w2t(f"[{now}] 文件 {docs} 数据已处理完毕") + w2t(f"[{now}] 文件 {docs} 数据已处理完毕\n") -def w2t_local(msg, wait, w2t): - while True: - global stop - if stop == 0 and wait != 0: - sleep(1) - w2t(msg, wait, 0, 'orange') - else: - break - - -def copy_data_to_result(df, ws_result, row_start, row_end, vel, trq, estop): - # 功能:将数据文件中有效数据拷贝至结果文件对应的 sheet - # 参数:如上 - # 返回值:- - # 结果文件数据清零 - +def data2result(df, ws_result, row_start, row_end, vel, trq, estop): data = [] - for _row in range(row_start, row_end + 1): - data.append(df.iloc[_row, vel - 1]) - data.append(df.iloc[_row, trq - 1]) - data.append(df.iloc[_row, estop - 1]) + for row in range(row_start, row_end): + data.append(df.iloc[row, vel - 1]) + data.append(df.iloc[row, trq - 1]) + data.append(df.iloc[row, estop - 1]) i = 0 - row_max = 2000 if row_end - row_start < 2000 else row_end - row_start + 20 - for _row in range(2, row_max): + row_max = 1000 if row_end - row_start < 1000 else row_end - row_start + 100 + for row in range(2, row_max): try: - ws_result.cell(row=_row, column=1).value = data[i] - ws_result.cell(row=_row, column=2).value = data[i + 1] - ws_result.cell(row=_row, column=3).value = data[i + 2] + ws_result.cell(row=row, column=1).value = data[i] + ws_result.cell(row=row, column=2).value = data[i + 1] + ws_result.cell(row=row, column=3).value = data[i + 2] i += 3 - except: - ws_result.cell(row=_row, column=1).value = None - ws_result.cell(row=_row, column=2).value = None - ws_result.cell(row=_row, column=3).value = None + except Exception: + ws_result.cell(row=row, column=1).value = None + ws_result.cell(row=row, column=2).value = None + ws_result.cell(row=row, column=3).value = None -def find_row_start(data_file, df, conditions, av, rr, vel, estop, w2t): - # 功能:查找数据文件中有效数据的行号,也即最后一个速度下降的点位 - # 参数:如上 - # 返回值:速度下降点位,最后的数据点位 +def get_row_range(data_file, df, conditions, av, rr, vel, estop, w2t): + row_start, row_end = 0, 0 ratio = float(conditions[2].removeprefix('speed')) / 100 av_max = av * ratio - row_max = df.index[-1] threshold = 0.95 - for _row in range(row_max, -1, -1): - if df.iloc[_row, estop - 1] != 0: - row_start = _row - 20 if _row - 20 > 0 else 0 + for row in range(df.index[-1] - 1, -1, -10): + if df.iloc[row, estop - 1] != 0: + row_start = row - 20 if row - 20 > 0 else 0 # 急停前找 20 个点 break else: - w2t(f"数据文件 {data_file} 采集的数据中没有 ESTOP 为非 0 的情况,需要确认", 0, 9, 'red') + w2t(f"数据文件 {data_file} 采集的数据中没有 ESTOP 为非 0 的情况,需要确认\n", "red", "StartNotFoundError") - for _row in range(row_start, row_max): - speed_row = (df.iloc[_row, vel - 1] * 180) / 3.1415926 * rr * 60 / 360 + for row in range(row_start, df.index[-1] - 1, 10): + speed_row = df.iloc[row, vel - 1] * clibs.RADIAN * rr * 60 / 360 if abs(speed_row) < 1: - row_end = _row + 100 if _row + 100 <= row_max else row_max + row_end = row + 100 if row + 100 <= df.index[-1] - 1 else df.index[-1] - 1 break else: - w2t(f"数据文件 {data_file} 最后的速度未降为零 ", 0, 10, 'red') + w2t(f"数据文件 {data_file} 最后的速度未降为零\n", "red", "SpeedNotZeroError") - av_estop = abs((df.iloc[row_start - 10:row_start + 10, vel - 1].abs().mean() * 180) / 3.1415926) + av_estop = abs(df.iloc[row_start - 20:row_start, vel - 1].abs().mean() * clibs.RADIAN) if abs(av_estop / av_max) < threshold: - filename = data_file.split('\\')[-1] - w2t(f"[av_estop: {av_estop:.2f} | shouldbe: {av_max:.2f}] 数据文件 {filename} 触发 ESTOP 时未采集到指定百分比的最大速度,需要检查", 0, 0, '#8A2BE2') + filename = data_file.split("/")[-1] + w2t(f"[av_estop: {av_estop:.2f} | shouldbe: {av_max:.2f}] 数据文件 {filename} 触发 ESTOP 时未采集到指定百分比的最大速度,需要检查\n", "#8A2BE2") return row_start, row_end -def find_result_sheet_name(conditions, count): - # 功能:获取结果文件准确的sheet页名称 - # 参数:臂展和速度的列表 - # 返回值:结果文件对应的sheet name - # 33%负载_33%速度_1 - ['loadxx', 'reachxx', 'speedxx'] - load = conditions[0].removeprefix('load') +def get_shtname(conditions, count): + # 33%负载_33%速度_1 - reach/load/speed + load = conditions[1].removeprefix('load') speed = conditions[2].removeprefix('speed') result_sheet_name = f"{load}%负载_{speed}%速度_{count}" return result_sheet_name -def single_file_process(data_file, wb_result, count, av, rr, vel, trq, estop, w2t): - # 功能:完成单个数据文件的处理 - # 参数:如上 - # 返回值:- - df = read_csv(data_file, sep='\t') +def single_file_process(data_file, wb, count, av, rr, vel, trq, estop, w2t): + df = pandas.read_csv(data_file, sep='\t') + conditions = data_file.split("/")[-2].split("_") # reach/load/speed + shtname = get_shtname(conditions, count) + ws = wb[shtname] - conditions = sorted(data_file.split('\\')[-2].split('_')) # ['loadxx', 'reachxx', 'speedxx'] - result_sheet_name = find_result_sheet_name(conditions, count) - ws_result = wb_result[result_sheet_name] - - row_start, row_end = find_row_start(data_file, df, conditions, av, rr, vel, estop, w2t) - copy_data_to_result(df, ws_result, row_start, row_end, vel, trq, estop) + row_start, row_end = get_row_range(data_file, df, conditions, av, rr, vel, estop, w2t) + data2result(df, ws, row_start, row_end, vel, trq, estop) -def data_process(result_file, raw_data_dirs, av, rr, vel, trq, estop, w2t): - # 功能:完成一个结果文件的数据处理 - # 参数:结果文件,数据目录,以及预读取的参数 - # 返回值:- - file_name = result_file.split('\\')[-1] - w2t(f"正在打开文件 {file_name} 需要 1min 左右", 1, 0, 'orange') +def data_process(result_file, rawdata_dirs, av, rr, vel, trq, estop, w2t): + filename = result_file.split("/")[-1] - global stop - stop = 0 - t_excel = clibs.GetThreadResult(load_workbook, args=(result_file,)) - t_wait = Thread(target=w2t_local, args=('.', 1, w2t)) + clibs.stop = True + w2t(f"正在打开文件 {filename} 需要 1min 左右......\n", "blue") + t_excel = clibs.GetThreadResult(openpyxl.load_workbook, args=(result_file, )) + t_excel.daemon = True t_excel.start() - t_wait.start() - t_excel.join() - wb_result = t_excel.get_result() - stop = 1 - sleep(1.1) - w2t('') + t_progress = threading.Thread(target=clibs.tl_prg, args=("Processing......", )) + t_progress.daemon = True + t_progress.start() + wb = t_excel.get_result() - prefix = result_file.split('\\')[-1].split('_')[0] - for raw_data_dir in raw_data_dirs: - if raw_data_dir.split('\\')[-1].split('_')[0] == prefix: - now_doing_msg(raw_data_dir, 'start', w2t) - _, data_files = clibs.traversal_files(raw_data_dir, w2t) + prefix = filename.split('_')[0] + for rawdata_dir in rawdata_dirs: + if rawdata_dir.split("/")[-1].split('_')[0] == prefix: + now_doing_msg(rawdata_dir, 'start', w2t) + _, data_files = clibs.traversal_files(rawdata_dir, w2t) # 数据文件串行处理模式--------------------------------- # count = 1 # for data_file in data_files: @@ -212,59 +193,41 @@ def data_process(result_file, raw_data_dirs, av, rr, vel, trq, estop, w2t): # --------------------------------------------------- # 数据文件并行处理模式--------------------------------- threads = [ - Thread(target=single_file_process, args=(data_files[0], wb_result, 1, av, rr, vel, trq, estop, w2t)), - Thread(target=single_file_process, args=(data_files[1], wb_result, 2, av, rr, vel, trq, estop, w2t)), - Thread(target=single_file_process, args=(data_files[2], wb_result, 3, av, rr, vel, trq, estop, w2t)) + threading.Thread(target=single_file_process, args=(data_files[0], wb, 1, av, rr, vel, trq, estop, w2t)), + threading.Thread(target=single_file_process, args=(data_files[1], wb, 2, av, rr, vel, trq, estop, w2t)), + threading.Thread(target=single_file_process, args=(data_files[2], wb, 3, av, rr, vel, trq, estop, w2t)) ] [t.start() for t in threads] [t.join() for t in threads] # --------------------------------------------------- - now_doing_msg(raw_data_dir, 'done', w2t) + now_doing_msg(rawdata_dir, 'done', w2t) - now_doing_msg(result_file, 'done', w2t) - w2t(f"正在保存文件 {file_name} 需要 1min 左右", 1, 0, 'orange') - stop = 0 - t_excel = Thread(target=wb_result.save, args=(result_file,)) - t_wait = Thread(target=w2t_local, args=('.', 1, w2t)) + w2t(f"正在保存文件 {filename} 需要 1min 左右......\n\n", "blue") + t_excel = threading.Thread(target=wb.save, args=(result_file, )) + t_excel.daemon = True t_excel.start() - t_wait.start() t_excel.join() - stop = 1 - sleep(1.1) - w2t('\n') + wb.close() + clibs.stop = False + t_progress.join() def main(): - # path, vel, trq, estop, w2t + time_start = time.time() path = clibs.data_dp["_path"] vel = int(clibs.data_dp["_vel"]) trq = int(clibs.data_dp["_trq"]) estop = int(clibs.data_dp["_estop"]) w2t = clibs.w2t - insert_logdb = clibs.insert_logdb - time_start = time.time() + rawdata_dirs, result_files = clibs.traversal_files(path, w2t) + config_file, result_files = check_files(rawdata_dirs, result_files, w2t) + av, rr = get_configs(config_file, w2t) - # threads = [] - check_files(path, rawdata_dirs, result_files, w2t) - # av, rr = get_configs(path + '\\configs.xlsx', w2t) - # - # prefix = [] - # for raw_data_dir in rawdata_dirs: - # prefix.append(raw_data_dir.split('\\')[-1].split("_")[0]) - # - # for result_file in result_files: - # if result_file.split('\\')[-1].split('_')[0] not in set(prefix): - # continue - # else: - # now_doing_msg(result_file, 'start', w2t) - # data_process(result_file, raw_data_dirs, av, rr, vel, trq, estop, w2t) - # # threads.append(Thread(target=data_process, args=(result_file, raw_data_dirs, av, rr, vel, trq, estop, w2t))) - # # [t.start() for t in threads] - # # [t.join() for t in threads] + for result_file in result_files: + data_process(result_file, rawdata_dirs, av, rr, vel, trq, estop, w2t) - w2t("----------------------------------------------------------\n") - w2t("全部处理完毕\n") + w2t("-"*60 + "\n全部处理完毕\n") time_end = time.time() time_total = time_end - time_start msg = f"数据处理时间:{time_total // 3600:02.0f} h {time_total % 3600 // 60:02.0f} m {time_total % 60:02.0f} s\n" diff --git a/code/data_process/current.py b/code/data_process/current.py index bb424f9..a08f0eb 100644 --- a/code/data_process/current.py +++ b/code/data_process/current.py @@ -4,6 +4,7 @@ import openpyxl import pandas import re import csv +import time from common import clibs @@ -161,12 +162,10 @@ def current_cycle(data_files, vel, trq, trqh, sensor, rrs, rcs, params, w2t, ins t_excel.daemon = True t_excel.start() t_excel.join() + wb.close() clibs.stop = False t_progress.join() - w2t("----------------------------------------------------------\n") - w2t("全部处理完毕") - def find_point(data_file, df, flag, row_s, row_e, threshold, step, end_point, skip_scale, axis, seq, w2t, insert_logdb): if flag == "lt": @@ -255,7 +254,7 @@ def p_single(wb, single, vel, trq, sensor, rrs, w2t, insert_logdb): row_e = df.index[-1] row_s = row_e - end_point speed_avg = df.iloc[row_s:row_e].abs().mean() - if speed_avg < 2: + if speed_avg < threshold: # 第一次过滤:消除速度为零的数据,找到速度即将大于零的上升临界点 row_s, row_e = find_point(data_file, df, "lt", row_s, row_e, threshold, step, end_point, skip_scale, axis, "pre-1", w2t, insert_logdb) row_e -= end_point*skip_scale @@ -281,7 +280,7 @@ def p_single(wb, single, vel, trq, sensor, rrs, w2t, insert_logdb): # 正式第三次采集:消除速度大于零的数据,找到速度即将趋近于零的下降临界点 row_s, row_e = find_point(data_file, df, "gt", row_s, row_e, threshold, step, end_point, skip_scale, axis, 3, w2t, insert_logdb) row_start = get_row_number(threshold, "start", df, row_s, row_e, axis, insert_logdb) - elif speed_avg > 2: + elif speed_avg > threshold: # 第一次过滤:消除速度大于零的数据,找到速度即将趋近于零的下降临界点 row_s, row_e = find_point(data_file, df, "gt", row_s, row_e, threshold, step, end_point, skip_scale, axis, "pre-1", w2t, insert_logdb) row_e -= end_point*skip_scale @@ -409,6 +408,7 @@ def get_configs(config_file, w2t, insert_logdb): def main(): + time_start = time.time() sub = clibs.data_dp["_sub"] path = clibs.data_dp["_path"] vel = int(clibs.data_dp["_vel"]) @@ -429,6 +429,12 @@ def main(): elif sub == "cycle": current_cycle(data_files, vel, trq, trqh, sensor, rrs, rcs, params, w2t, insert_logdb) + w2t("-"*60 + "\n全部处理完毕\n") + time_end = time.time() + time_total = time_end - time_start + msg = f"数据处理时间:{time_total // 3600:02.0f} h {time_total % 3600 // 60:02.0f} m {time_total % 60:02.0f} s\n" + w2t(msg) + if __name__ == '__main__': main()