add @property deco and rewrite connection logic
This commit is contained in:
parent
50f150d685
commit
b381ee92f5
107
code/openapi.py
107
code/openapi.py
@ -9,7 +9,6 @@ from pymodbus.client.tcp import ModbusTcpClient
|
|||||||
# from pymodbus.payload import BinaryPayloadDecoder, BinaryPayloadBuilder
|
# from pymodbus.payload import BinaryPayloadDecoder, BinaryPayloadBuilder
|
||||||
# from pymodbus.constants import Endian
|
# from pymodbus.constants import Endian
|
||||||
from paramiko import SSHClient, AutoAddPolicy
|
from paramiko import SSHClient, AutoAddPolicy
|
||||||
from datetime import datetime
|
|
||||||
import clibs
|
import clibs
|
||||||
|
|
||||||
|
|
||||||
@ -121,99 +120,118 @@ class ModbusRequest(object):
|
|||||||
# clibs.logger.info(f"[NG]-40018-{action} 执行{actions}安全区 safe region 03")
|
# clibs.logger.info(f"[NG]-40018-{action} 执行{actions}安全区 safe region 03")
|
||||||
# sleep(clibs.interval)
|
# sleep(clibs.interval)
|
||||||
|
|
||||||
|
@property
|
||||||
def w_alarm_state(self): # OK
|
def w_alarm_state(self): # OK
|
||||||
res = self.__c.read_holding_registers(40500, 1).registers[0]
|
res = self.__c.read_holding_registers(40500, 1).registers[0]
|
||||||
clibs.logger.info(f"40500 获取告警状态,结果为 {res} :--: 0 表示无告警, 1 表示有告警")
|
clibs.logger.info(f"40500 获取告警状态,结果为 {res} :--: 0 表示无告警, 1 表示有告警")
|
||||||
return res
|
return res
|
||||||
|
|
||||||
|
@property
|
||||||
def w_collision_alarm_state(self): # OK
|
def w_collision_alarm_state(self): # OK
|
||||||
res = self.__c.read_holding_registers(40501, 1).registers[0]
|
res = self.__c.read_holding_registers(40501, 1).registers[0]
|
||||||
clibs.logger.info(f"40501 获取碰撞告警状态,结果为 {res} :--: 0 表示未触发 1 表示已触发")
|
clibs.logger.info(f"40501 获取碰撞告警状态,结果为 {res} :--: 0 表示未触发 1 表示已触发")
|
||||||
return res
|
return res
|
||||||
|
|
||||||
|
@property
|
||||||
def w_collision_open_state(self): # OK
|
def w_collision_open_state(self): # OK
|
||||||
res = self.__c.read_holding_registers(40502, 1).registers[0]
|
res = self.__c.read_holding_registers(40502, 1).registers[0]
|
||||||
clibs.logger.info(f"40502 获取碰撞检测开启状态,结果为 {res} :--: 0 表示关闭 1 表示开启")
|
clibs.logger.info(f"40502 获取碰撞检测开启状态,结果为 {res} :--: 0 表示关闭 1 表示开启")
|
||||||
return res
|
return res
|
||||||
|
|
||||||
|
@property
|
||||||
def w_controller_is_running(self): # OK
|
def w_controller_is_running(self): # OK
|
||||||
res = self.__c.read_holding_registers(40503, 1).registers[0]
|
res = self.__c.read_holding_registers(40503, 1).registers[0]
|
||||||
clibs.logger.info(f"40503 获取控制器运行状态,结果为 {res} :--: 0 表示运行异常 1 表示运行正常")
|
clibs.logger.info(f"40503 获取控制器运行状态,结果为 {res} :--: 0 表示运行异常 1 表示运行正常")
|
||||||
return res
|
return res
|
||||||
|
|
||||||
|
@property
|
||||||
def w_encoder_low_battery(self): # OK
|
def w_encoder_low_battery(self): # OK
|
||||||
res = self.__c.read_holding_registers(40504, 1).registers[0]
|
res = self.__c.read_holding_registers(40504, 1).registers[0]
|
||||||
clibs.logger.info(f"40504 获取编码器低电压状态,结果为 {res} :--: 0 表示非低电压 1 表示低电压 需关注")
|
clibs.logger.info(f"40504 获取编码器低电压状态,结果为 {res} :--: 0 表示非低电压 1 表示低电压 需关注")
|
||||||
return res
|
return res
|
||||||
|
|
||||||
|
@property
|
||||||
def w_estop_state(self): # OK
|
def w_estop_state(self): # OK
|
||||||
res = self.__c.read_holding_registers(40505, 1).registers[0]
|
res = self.__c.read_holding_registers(40505, 1).registers[0]
|
||||||
clibs.logger.info(f"40505 获取机器人急停状态(非软急停),结果为 {res} :--: 0 表示未触发 1 表示已触发")
|
clibs.logger.info(f"40505 获取机器人急停状态(非软急停),结果为 {res} :--: 0 表示未触发 1 表示已触发")
|
||||||
return res
|
return res
|
||||||
|
|
||||||
|
@property
|
||||||
def w_motor_state(self): # OK
|
def w_motor_state(self): # OK
|
||||||
res = self.__c.read_holding_registers(40506, 1).registers[0]
|
res = self.__c.read_holding_registers(40506, 1).registers[0]
|
||||||
clibs.logger.info(f"40506 获取机器人上电状态,结果为 {res} :--: 0 表示未上电 1 表示已上电")
|
clibs.logger.info(f"40506 获取机器人上电状态,结果为 {res} :--: 0 表示未上电 1 表示已上电")
|
||||||
return res
|
return res
|
||||||
|
|
||||||
|
@property
|
||||||
def w_operation_mode(self): # OK
|
def w_operation_mode(self): # OK
|
||||||
res = self.__c.read_holding_registers(40507, 1).registers[0]
|
res = self.__c.read_holding_registers(40507, 1).registers[0]
|
||||||
clibs.logger.info(f"40507 获取机器人操作模式,结果为 {res} :--: 0 表示手动模式 1 表示自动模式")
|
clibs.logger.info(f"40507 获取机器人操作模式,结果为 {res} :--: 0 表示手动模式 1 表示自动模式")
|
||||||
return res
|
return res
|
||||||
|
|
||||||
|
@property
|
||||||
def w_program_state(self): # OK
|
def w_program_state(self): # OK
|
||||||
res = self.__c.read_holding_registers(40508, 1).registers[0]
|
res = self.__c.read_holding_registers(40508, 1).registers[0]
|
||||||
clibs.logger.info(f"40508 获取程序的运行状态,结果为 {res} :--: 0 表示未运行 1 表示正在运行")
|
clibs.logger.info(f"40508 获取程序的运行状态,结果为 {res} :--: 0 表示未运行 1 表示正在运行")
|
||||||
return res
|
return res
|
||||||
|
|
||||||
|
@property
|
||||||
def w_program_not_run(self): # OK
|
def w_program_not_run(self): # OK
|
||||||
res = self.__c.read_holding_registers(40509, 1).registers[0]
|
res = self.__c.read_holding_registers(40509, 1).registers[0]
|
||||||
clibs.logger.info(f"40509 判定程序为未运行状态,结果为 {res} :--: 0 表示正在运行 1 表示未运行")
|
clibs.logger.info(f"40509 判定程序为未运行状态,结果为 {res} :--: 0 表示正在运行 1 表示未运行")
|
||||||
return res
|
return res
|
||||||
|
|
||||||
|
@property
|
||||||
def w_program_reset(self): # OK
|
def w_program_reset(self): # OK
|
||||||
res = self.__c.read_holding_registers(40510, 1).registers[0]
|
res = self.__c.read_holding_registers(40510, 1).registers[0]
|
||||||
clibs.logger.info(f"40510 判定程序指针为 pp2main 状态,结果为 {res} :--: 0 表示指针不在 main 函数 1 表示指针在 main 函数")
|
clibs.logger.info(f"40510 判定程序指针为 pp2main 状态,结果为 {res} :--: 0 表示指针不在 main 函数 1 表示指针在 main 函数")
|
||||||
return res
|
return res
|
||||||
|
|
||||||
|
@property
|
||||||
def w_reduce_mode_state(self): # OK
|
def w_reduce_mode_state(self): # OK
|
||||||
res = self.__c.read_holding_registers(40511, 1).registers[0]
|
res = self.__c.read_holding_registers(40511, 1).registers[0]
|
||||||
clibs.logger.info(f"40511 获取机器人缩减模式状态,结果为 {res} :--: 0 表示非缩减模式 1 表示缩减模式")
|
clibs.logger.info(f"40511 获取机器人缩减模式状态,结果为 {res} :--: 0 表示非缩减模式 1 表示缩减模式")
|
||||||
return res
|
return res
|
||||||
|
|
||||||
|
@property
|
||||||
def w_robot_is_busy(self): # OK
|
def w_robot_is_busy(self): # OK
|
||||||
res = self.__c.read_holding_registers(40512, 1).registers[0]
|
res = self.__c.read_holding_registers(40512, 1).registers[0]
|
||||||
clibs.logger.info(f"40512 获取机器人是否处于 busy 状态,结果为 {res} :--: 0 表示未处于 busy 状态 1 表示处于 busy 状态")
|
clibs.logger.info(f"40512 获取机器人是否处于 busy 状态,结果为 {res} :--: 0 表示未处于 busy 状态 1 表示处于 busy 状态")
|
||||||
return res
|
return res
|
||||||
|
|
||||||
def w_robot_moving(self): # OK
|
@property
|
||||||
|
def w_robot_is_moving(self): # OK
|
||||||
res = self.__c.read_holding_registers(40513, 1).registers[0]
|
res = self.__c.read_holding_registers(40513, 1).registers[0]
|
||||||
clibs.logger.info(f"40513 获取机器人是否处于运动状态,结果为 {res} :--: 0 表示为运动 1 表示正在运动")
|
clibs.logger.info(f"40513 获取机器人是否处于运动状态,结果为 {res} :--: 0 表示为运动 1 表示正在运动")
|
||||||
return res
|
return res
|
||||||
|
|
||||||
|
@property
|
||||||
def w_safe_door_state(self): # OK
|
def w_safe_door_state(self): # OK
|
||||||
res = self.__c.read_holding_registers(40514, 1).registers[0]
|
res = self.__c.read_holding_registers(40514, 1).registers[0]
|
||||||
clibs.logger.info(f"40514 获取机器人是否处于安全门打开状态,需自动模式下执行,结果为 {res} :--: 0 表示未触发安全门 1 表示已触发安全门")
|
clibs.logger.info(f"40514 获取机器人是否处于安全门打开状态,需自动模式下执行,结果为 {res} :--: 0 表示未触发安全门 1 表示已触发安全门")
|
||||||
return res
|
return res
|
||||||
|
|
||||||
|
@property
|
||||||
def w_safe_region01(self): # NG
|
def w_safe_region01(self): # NG
|
||||||
clibs.logger.critical(f"40515 获取安全区域 safe region01 功能咱不可用,待修复...")
|
clibs.logger.critical(f"40515 获取安全区域 safe region01 功能咱不可用,待修复...")
|
||||||
# res = self.__c.read_holding_registers(40515, 1).registers[0]
|
# res = self.__c.read_holding_registers(40515, 1).registers[0]
|
||||||
# clibs.logger.info(f"40515 获取安全区域 safe region01 是否处于打开状态,结果为 {res}")
|
# clibs.logger.info(f"40515 获取安全区域 safe region01 是否处于打开状态,结果为 {res}")
|
||||||
# return res
|
# return res
|
||||||
|
|
||||||
|
@property
|
||||||
def w_safe_region02(self): # NG
|
def w_safe_region02(self): # NG
|
||||||
clibs.logger.critical(f"40516 获取安全区域 safe region02 功能咱不可用,待修复...")
|
clibs.logger.critical(f"40516 获取安全区域 safe region02 功能咱不可用,待修复...")
|
||||||
# res = self.__c.read_holding_registers(40516, 1).registers[0]
|
# res = self.__c.read_holding_registers(40516, 1).registers[0]
|
||||||
# clibs.logger.info(f"40516 获取安全区域 safe region02 是否处于打开状态,结果为 {res}")
|
# clibs.logger.info(f"40516 获取安全区域 safe region02 是否处于打开状态,结果为 {res}")
|
||||||
# return res
|
# return res
|
||||||
|
|
||||||
|
@property
|
||||||
def w_safe_region03(self): # NG
|
def w_safe_region03(self): # NG
|
||||||
clibs.logger.critical(f"40517 获取安全区域 safe region03 功能咱不可用,待修复...")
|
clibs.logger.critical(f"40517 获取安全区域 safe region03 功能咱不可用,待修复...")
|
||||||
# res = self.__c.read_holding_registers(40517, 1).registers[0]
|
# res = self.__c.read_holding_registers(40517, 1).registers[0]
|
||||||
# clibs.logger.info(f"40517 获取安全区域 safe region03 是否处于打开状态,结果为 {res}")
|
# clibs.logger.info(f"40517 获取安全区域 safe region03 是否处于打开状态,结果为 {res}")
|
||||||
# return res
|
# return res
|
||||||
|
|
||||||
|
@property
|
||||||
def w_soft_estop_state(self): # OK
|
def w_soft_estop_state(self): # OK
|
||||||
res = self.__c.read_holding_registers(40518, 1).registers[0]
|
res = self.__c.read_holding_registers(40518, 1).registers[0]
|
||||||
clibs.logger.info(f"40518 获取机器人软急停状态,结果为 {res} :--: 0 表示未触发软急停 1 表示已触发软急停")
|
clibs.logger.info(f"40518 获取机器人软急停状态,结果为 {res} :--: 0 表示未触发软急停 1 表示已触发软急停")
|
||||||
@ -248,7 +266,6 @@ class HmiRequest(object):
|
|||||||
self.__flag = 0
|
self.__flag = 0
|
||||||
self.__response = ""
|
self.__response = ""
|
||||||
self.__leftover = 0
|
self.__leftover = 0
|
||||||
self.__flag_xs = 0
|
|
||||||
self.__response_xs = ""
|
self.__response_xs = ""
|
||||||
self.__is_connected = False
|
self.__is_connected = False
|
||||||
self.__silence = False
|
self.__silence = False
|
||||||
@ -259,8 +276,8 @@ class HmiRequest(object):
|
|||||||
self.__index = 0
|
self.__index = 0
|
||||||
self.__reset_index = 0
|
self.__reset_index = 0
|
||||||
self.__close_hmi = False
|
self.__close_hmi = False
|
||||||
|
self.__error_code = 0
|
||||||
|
|
||||||
# self.__sock_conn()
|
|
||||||
self.__t_is_alive = Thread(target=self.__is_alive)
|
self.__t_is_alive = Thread(target=self.__is_alive)
|
||||||
self.__t_is_alive.daemon = False
|
self.__t_is_alive.daemon = False
|
||||||
self.__t_is_alive.start()
|
self.__t_is_alive.start()
|
||||||
@ -290,10 +307,6 @@ class HmiRequest(object):
|
|||||||
|
|
||||||
sleep(clibs.interval*10)
|
sleep(clibs.interval*10)
|
||||||
|
|
||||||
@property
|
|
||||||
def connection_state(self):
|
|
||||||
return self.__is_connected
|
|
||||||
|
|
||||||
def close(self):
|
def close(self):
|
||||||
self.__close_hmi = True
|
self.__close_hmi = True
|
||||||
self.__is_connected = False
|
self.__is_connected = False
|
||||||
@ -309,22 +322,26 @@ class HmiRequest(object):
|
|||||||
self.__c_xs.setblocking(True)
|
self.__c_xs.setblocking(True)
|
||||||
|
|
||||||
# 尝试连续三次发送心跳包,确认建联成功
|
# 尝试连续三次发送心跳包,确认建联成功
|
||||||
for _ in range(3):
|
self.__error_code = 0
|
||||||
|
for i in range(3):
|
||||||
self.execution("controller.heart")
|
self.execution("controller.heart")
|
||||||
sleep(clibs.interval)
|
sleep(clibs.interval/5)
|
||||||
else:
|
if not self.__error_code:
|
||||||
self.__is_connected = True
|
self.__is_connected = True
|
||||||
clibs.logger.success("HMI connection success...")
|
clibs.logger.success("HMI connection success...")
|
||||||
|
else:
|
||||||
|
raise Exception()
|
||||||
|
|
||||||
except Exception as Err:
|
except Exception as Err:
|
||||||
self.__sth_wrong(9, f"HMI connection failed...{Err}")
|
self.__sth_wrong(9, f"HMI connection failed...{Err}")
|
||||||
|
|
||||||
def __sth_wrong(self, ex_code, err_desc=""):
|
def __sth_wrong(self, exit_code, err_desc=""):
|
||||||
self.__is_connected = False
|
self.__is_connected = False
|
||||||
|
self.__error_code = exit_code
|
||||||
if not self.__silence:
|
if not self.__silence:
|
||||||
clibs.logger.error(f"[{ex_code}] 可能是 HMI 无法连接到 {clibs.ip_addr}:{clibs.socket_port}...")
|
clibs.logger.error(f"[{exit_code}] 可能是 HMI 无法连接到 {clibs.ip_addr}:{clibs.socket_port}...")
|
||||||
if err_desc != "":
|
if err_desc != "":
|
||||||
clibs.logger.error(f"[{ex_code}] {err_desc}")
|
clibs.logger.error(f"[{exit_code}] {err_desc}")
|
||||||
# exit(ex_code)
|
|
||||||
|
|
||||||
def __header_check(self, index, data):
|
def __header_check(self, index, data):
|
||||||
if index + 8 < len(data):
|
if index + 8 < len(data):
|
||||||
@ -616,7 +633,7 @@ class HmiRequest(object):
|
|||||||
def execution(self, command, protocol_flag=0, **kwargs):
|
def execution(self, command, protocol_flag=0, **kwargs):
|
||||||
def log_reqs(request):
|
def log_reqs(request):
|
||||||
with open(clibs.log_data_reqs, mode="a", encoding="utf-8") as f_log:
|
with open(clibs.log_data_reqs, mode="a", encoding="utf-8") as f_log:
|
||||||
log_time = datetime.now().strftime('%Y-%m-%d %H:%M:%S.%f')[:-3]
|
log_time = strftime("%Y-%m-%d %H:%M:%S", localtime(time()))
|
||||||
f_log.write(" ".join([log_time, dumps(req), "\n"]))
|
f_log.write(" ".join([log_time, dumps(req), "\n"]))
|
||||||
|
|
||||||
if protocol_flag == 0: # for old protocols
|
if protocol_flag == 0: # for old protocols
|
||||||
@ -888,7 +905,7 @@ class HmiRequest(object):
|
|||||||
self.__sth_wrong("3min 内未能完成重新连接,需要查看后台控制器是否正常启动,或者 ip/port 是否正确")
|
self.__sth_wrong("3min 内未能完成重新连接,需要查看后台控制器是否正常启动,或者 ip/port 是否正确")
|
||||||
break
|
break
|
||||||
for _ in range(3):
|
for _ in range(3):
|
||||||
if not self.connection_state:
|
if not self.__is_connected:
|
||||||
break
|
break
|
||||||
sleep(2)
|
sleep(2)
|
||||||
else:
|
else:
|
||||||
@ -902,6 +919,7 @@ class HmiRequest(object):
|
|||||||
"""
|
"""
|
||||||
self.execution("io_device.load_cfg")
|
self.execution("io_device.load_cfg")
|
||||||
|
|
||||||
|
@property
|
||||||
def get_quickturn_pos(self):
|
def get_quickturn_pos(self):
|
||||||
"""
|
"""
|
||||||
获取机器人的home位姿、拖动位姿和发货位姿,轴关节角度,end_posture 取值如下:
|
获取机器人的home位姿、拖动位姿和发货位姿,轴关节角度,end_posture 取值如下:
|
||||||
@ -961,6 +979,7 @@ class HmiRequest(object):
|
|||||||
"""
|
"""
|
||||||
self.execution("move.stop", stoptype=stoptype)
|
self.execution("move.stop", stoptype=stoptype)
|
||||||
|
|
||||||
|
@property
|
||||||
def get_jog_params(self):
|
def get_jog_params(self):
|
||||||
"""
|
"""
|
||||||
获取JOG的参数
|
获取JOG的参数
|
||||||
@ -999,6 +1018,7 @@ class HmiRequest(object):
|
|||||||
"""
|
"""
|
||||||
self.execution("jog.start", index=index, direction=direction, is_ext=is_ext)
|
self.execution("jog.start", index=index, direction=direction, is_ext=is_ext)
|
||||||
|
|
||||||
|
@property
|
||||||
def get_socket_params(self):
|
def get_socket_params(self):
|
||||||
"""
|
"""
|
||||||
获取socket参数
|
获取socket参数
|
||||||
@ -1035,6 +1055,7 @@ class HmiRequest(object):
|
|||||||
"""
|
"""
|
||||||
self.execution("socket.set_params", enable=enable, ip=ip, name=name, port=port, suffix=suffix, type=type, reconnect_flag=reconnect_flag, auto_connect=auto_connect, disconnection_triggering_behavior=disconnection_triggering_behavior, disconnection_detection_time=disconnection_detection_time)
|
self.execution("socket.set_params", enable=enable, ip=ip, name=name, port=port, suffix=suffix, type=type, reconnect_flag=reconnect_flag, auto_connect=auto_connect, disconnection_triggering_behavior=disconnection_triggering_behavior, disconnection_detection_time=disconnection_detection_time)
|
||||||
|
|
||||||
|
@property
|
||||||
def get_diagnosis_params(self, version="1.4.1"):
|
def get_diagnosis_params(self, version="1.4.1"):
|
||||||
"""
|
"""
|
||||||
获取诊断功能开启状态,以及相应其他信息
|
获取诊断功能开启状态,以及相应其他信息
|
||||||
@ -1112,6 +1133,7 @@ class HmiRequest(object):
|
|||||||
"""
|
"""
|
||||||
self.execution("diagnosis.save", save=save)
|
self.execution("diagnosis.save", save=save)
|
||||||
|
|
||||||
|
@property
|
||||||
def qurry_system_io_configuration(self):
|
def qurry_system_io_configuration(self):
|
||||||
"""
|
"""
|
||||||
系统IO配置的查询协议,trigger 参数取值参照如下:
|
系统IO配置的查询协议,trigger 参数取值参照如下:
|
||||||
@ -1144,6 +1166,7 @@ class HmiRequest(object):
|
|||||||
"""
|
"""
|
||||||
return self.__get_data(currentframe().f_code.co_name, "system_io.query_configuration")
|
return self.__get_data(currentframe().f_code.co_name, "system_io.query_configuration")
|
||||||
|
|
||||||
|
@property
|
||||||
def qurry_system_io_event_configuration(self):
|
def qurry_system_io_event_configuration(self):
|
||||||
"""
|
"""
|
||||||
查询当前系统支持的系统IO事件列表,包括事件key、名称、支持的触发方式等配置
|
查询当前系统支持的系统IO事件列表,包括事件key、名称、支持的触发方式等配置
|
||||||
@ -1210,6 +1233,7 @@ class HmiRequest(object):
|
|||||||
output_system_io[o_func] = {"signal": o_signals[_index]}
|
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)
|
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):
|
def get_fieldbus_device_params(self):
|
||||||
"""
|
"""
|
||||||
获取设备列表的开关状态
|
获取设备列表的开关状态
|
||||||
@ -1244,6 +1268,7 @@ class HmiRequest(object):
|
|||||||
"""
|
"""
|
||||||
self.execution("fieldbus_device.load_cfg")
|
self.execution("fieldbus_device.load_cfg")
|
||||||
|
|
||||||
|
@property
|
||||||
def get_modbus_params(self):
|
def get_modbus_params(self):
|
||||||
"""
|
"""
|
||||||
获取modbus参数
|
获取modbus参数
|
||||||
@ -1285,6 +1310,7 @@ class HmiRequest(object):
|
|||||||
"""
|
"""
|
||||||
return self.__get_data(currentframe().f_code.co_name, "modbus.get_values", mode=mode)
|
return self.__get_data(currentframe().f_code.co_name, "modbus.get_values", mode=mode)
|
||||||
|
|
||||||
|
@property
|
||||||
def get_soft_limit_params(self):
|
def get_soft_limit_params(self):
|
||||||
"""
|
"""
|
||||||
获取软限位参数
|
获取软限位参数
|
||||||
@ -1311,6 +1337,7 @@ class HmiRequest(object):
|
|||||||
"""
|
"""
|
||||||
self.execution("soft_limit.set_params", enable=enable, upper=upper, lower=lower, reduced_upper=reduced_upper, reduced_lower=reduced_lower)
|
self.execution("soft_limit.set_params", enable=enable, upper=upper, lower=lower, reduced_upper=reduced_upper, reduced_lower=reduced_lower)
|
||||||
|
|
||||||
|
@property
|
||||||
def get_device_params(self):
|
def get_device_params(self):
|
||||||
"""
|
"""
|
||||||
获取设备信息
|
获取设备信息
|
||||||
@ -1318,6 +1345,7 @@ class HmiRequest(object):
|
|||||||
"""
|
"""
|
||||||
return self.__get_data(currentframe().f_code.co_name, "device.get_params")
|
return self.__get_data(currentframe().f_code.co_name, "device.get_params")
|
||||||
|
|
||||||
|
@property
|
||||||
def get_cart_pos(self):
|
def get_cart_pos(self):
|
||||||
"""
|
"""
|
||||||
获取机器人的当前位姿:包括轴关节角度,笛卡尔关节角度,四元数,欧拉角(臂角)
|
获取机器人的当前位姿:包括轴关节角度,笛卡尔关节角度,四元数,欧拉角(臂角)
|
||||||
@ -1333,6 +1361,7 @@ class HmiRequest(object):
|
|||||||
"""
|
"""
|
||||||
return self.__get_data(currentframe().f_code.co_name, "move.get_pos")
|
return self.__get_data(currentframe().f_code.co_name, "move.get_pos")
|
||||||
|
|
||||||
|
@property
|
||||||
def get_joint_pos(self):
|
def get_joint_pos(self):
|
||||||
"""
|
"""
|
||||||
获取机器人的当前关节角度:包括内部轴和外部轴
|
获取机器人的当前关节角度:包括内部轴和外部轴
|
||||||
@ -1344,6 +1373,7 @@ class HmiRequest(object):
|
|||||||
"""
|
"""
|
||||||
return self.__get_data(currentframe().f_code.co_name, "move.get_joint_pos")
|
return self.__get_data(currentframe().f_code.co_name, "move.get_joint_pos")
|
||||||
|
|
||||||
|
@property
|
||||||
def get_monitor_cfg(self):
|
def get_monitor_cfg(self):
|
||||||
"""
|
"""
|
||||||
获取机器人的监控配置参数,RefCoordinateType 类型数据,表示当前控制器位置监测的相对坐标系
|
获取机器人的监控配置参数,RefCoordinateType 类型数据,表示当前控制器位置监测的相对坐标系
|
||||||
@ -1365,6 +1395,7 @@ class HmiRequest(object):
|
|||||||
"""
|
"""
|
||||||
self.execution("move.set_monitor_cfg", ref_coordinate=ref_coordinate)
|
self.execution("move.set_monitor_cfg", ref_coordinate=ref_coordinate)
|
||||||
|
|
||||||
|
@property
|
||||||
def get_move_params(self):
|
def get_move_params(self):
|
||||||
"""
|
"""
|
||||||
获取机器人的运动参数:包括减速比、耦合比、最大速度、加速度、加加速度、acc ramp time、规划步长等信息
|
获取机器人的运动参数:包括减速比、耦合比、最大速度、加速度、加加速度、acc ramp time、规划步长等信息
|
||||||
@ -1408,6 +1439,7 @@ class HmiRequest(object):
|
|||||||
"""
|
"""
|
||||||
self.execution("move.set_params", JOINT_MAX_SPEED=JOINT_MAX_SPEED, JOINT_MAX_ACC=JOINT_MAX_ACC, JOINT_MAX_JERK=JOINT_MAX_JERK, TCP_MAX_SPEED=TCP_MAX_SPEED, DEFAULT_ACC_PARAMS=DEFAULT_ACC_PARAMS, VEL_SMOOTH_FACTOR=VEL_SMOOTH_FACTOR, ACC_RAMPTIME_JOG=ACC_RAMPTIME_JOG)
|
self.execution("move.set_params", JOINT_MAX_SPEED=JOINT_MAX_SPEED, JOINT_MAX_ACC=JOINT_MAX_ACC, JOINT_MAX_JERK=JOINT_MAX_JERK, TCP_MAX_SPEED=TCP_MAX_SPEED, DEFAULT_ACC_PARAMS=DEFAULT_ACC_PARAMS, VEL_SMOOTH_FACTOR=VEL_SMOOTH_FACTOR, ACC_RAMPTIME_JOG=ACC_RAMPTIME_JOG)
|
||||||
|
|
||||||
|
@property
|
||||||
def get_quick_stop_distance(self):
|
def get_quick_stop_distance(self):
|
||||||
"""
|
"""
|
||||||
获取机器人 search 指令最大停止距离
|
获取机器人 search 指令最大停止距离
|
||||||
@ -1426,6 +1458,7 @@ class HmiRequest(object):
|
|||||||
"""
|
"""
|
||||||
self.execution("move.set_quickstop_distance", distance=distance)
|
self.execution("move.set_quickstop_distance", distance=distance)
|
||||||
|
|
||||||
|
@property
|
||||||
def get_collision_params(self):
|
def get_collision_params(self):
|
||||||
"""
|
"""
|
||||||
获取碰撞检测相关参数
|
获取碰撞检测相关参数
|
||||||
@ -1474,6 +1507,7 @@ class HmiRequest(object):
|
|||||||
"""
|
"""
|
||||||
self.execution("collision.set_state", collision_state=collision_state)
|
self.execution("collision.set_state", collision_state=collision_state)
|
||||||
|
|
||||||
|
@property
|
||||||
def get_robot_state(self):
|
def get_robot_state(self):
|
||||||
"""
|
"""
|
||||||
{
|
{
|
||||||
@ -1496,6 +1530,7 @@ class HmiRequest(object):
|
|||||||
"""
|
"""
|
||||||
self.execution("controller.set_params", time=robot_time)
|
self.execution("controller.set_params", time=robot_time)
|
||||||
|
|
||||||
|
@property
|
||||||
def get_robot_params(self):
|
def get_robot_params(self):
|
||||||
"""
|
"""
|
||||||
"alias": "",
|
"alias": "",
|
||||||
@ -1533,6 +1568,7 @@ class HmiRequest(object):
|
|||||||
case _:
|
case _:
|
||||||
clibs.logger.error("switch_tp_mode 参数错误 非法参数,只接受 with/without")
|
clibs.logger.error("switch_tp_mode 参数错误 非法参数,只接受 with/without")
|
||||||
|
|
||||||
|
@property
|
||||||
def get_tp_mode(self):
|
def get_tp_mode(self):
|
||||||
"""
|
"""
|
||||||
获取示教器连接状态
|
获取示教器连接状态
|
||||||
@ -1543,6 +1579,7 @@ class HmiRequest(object):
|
|||||||
"""
|
"""
|
||||||
return self.__get_data(currentframe().f_code.co_name, "state.get_tp_mode")
|
return self.__get_data(currentframe().f_code.co_name, "state.get_tp_mode")
|
||||||
|
|
||||||
|
@property
|
||||||
def get_drag_params(self):
|
def get_drag_params(self):
|
||||||
"""
|
"""
|
||||||
获取拖动模式参数
|
获取拖动模式参数
|
||||||
@ -1581,6 +1618,7 @@ class HmiRequest(object):
|
|||||||
"""
|
"""
|
||||||
self.execution("safety.safety_area.overall_enable", protocol_flag=1, enable=enable)
|
self.execution("safety.safety_area.overall_enable", protocol_flag=1, enable=enable)
|
||||||
|
|
||||||
|
@property
|
||||||
def get_safety_area_params(self):
|
def get_safety_area_params(self):
|
||||||
"""
|
"""
|
||||||
获取安全区所有的配置信息
|
获取安全区所有的配置信息
|
||||||
@ -1698,6 +1736,7 @@ class HmiRequest(object):
|
|||||||
"""
|
"""
|
||||||
self.execution("safety.safety_area.safety_area_enable", protocol_flag=1, id=id, enable=enable, **kwargs)
|
self.execution("safety.safety_area.safety_area_enable", protocol_flag=1, id=id, enable=enable, **kwargs)
|
||||||
|
|
||||||
|
@property
|
||||||
def get_filtered_error_code(self):
|
def get_filtered_error_code(self):
|
||||||
"""
|
"""
|
||||||
获取已设定的错误码过滤列表
|
获取已设定的错误码过滤列表
|
||||||
@ -1875,105 +1914,139 @@ class ExternalCommunication(object):
|
|||||||
return self.__exec_cmd(f"set_robot_time:{robot_time}", f"修改控制器和示教器的时间为 {robot_time}")
|
return self.__exec_cmd(f"set_robot_time:{robot_time}", f"修改控制器和示教器的时间为 {robot_time}")
|
||||||
|
|
||||||
# --------------------------------------------------------------------------------------------------
|
# --------------------------------------------------------------------------------------------------
|
||||||
|
@property
|
||||||
def motor_on_state(self):
|
def motor_on_state(self):
|
||||||
return self.__exec_cmd("motor_on_state", "电机上电状态")
|
return self.__exec_cmd("motor_on_state", "电机上电状态")
|
||||||
|
|
||||||
|
@property
|
||||||
def robot_running_state(self):
|
def robot_running_state(self):
|
||||||
return self.__exec_cmd("robot_running_state", "程序运行状态")
|
return self.__exec_cmd("robot_running_state", "程序运行状态")
|
||||||
|
|
||||||
|
@property
|
||||||
def estop_state(self):
|
def estop_state(self):
|
||||||
return self.__exec_cmd("estop_state", "急停状态")
|
return self.__exec_cmd("estop_state", "急停状态")
|
||||||
|
|
||||||
|
@property
|
||||||
def operation_mode(self):
|
def operation_mode(self):
|
||||||
return self.__exec_cmd("operating_mode", "工作模式")
|
return self.__exec_cmd("operating_mode", "工作模式")
|
||||||
|
|
||||||
|
@property
|
||||||
def home_state(self):
|
def home_state(self):
|
||||||
return self.__exec_cmd("home_state", "HOME 输出状态")
|
return self.__exec_cmd("home_state", "HOME 输出状态")
|
||||||
|
|
||||||
|
@property
|
||||||
def fault_state(self):
|
def fault_state(self):
|
||||||
return self.__exec_cmd("fault_state", "故障状态")
|
return self.__exec_cmd("fault_state", "故障状态")
|
||||||
|
|
||||||
|
@property
|
||||||
def collision_state(self):
|
def collision_state(self):
|
||||||
return self.__exec_cmd("collision_state", "碰撞检测状态")
|
return self.__exec_cmd("collision_state", "碰撞检测状态")
|
||||||
|
|
||||||
|
@property
|
||||||
def task_state(self):
|
def task_state(self):
|
||||||
return self.__exec_cmd("task_state", "获取机器人运行任务状态")
|
return self.__exec_cmd("task_state", "获取机器人运行任务状态")
|
||||||
|
|
||||||
|
@property
|
||||||
def get_cart_pos(self): # cart_pos/cart_pos_name 都可以正常返回,区别在返回的前缀,可测试辨别
|
def get_cart_pos(self): # cart_pos/cart_pos_name 都可以正常返回,区别在返回的前缀,可测试辨别
|
||||||
return self.__exec_cmd("cart_pos", "获取笛卡尔位置")
|
return self.__exec_cmd("cart_pos", "获取笛卡尔位置")
|
||||||
|
|
||||||
|
@property
|
||||||
def get_joint_pos(self): # jnt_pos/jnt_pos_name 都可以正常返回,区别在返回的前缀,可测试辨别
|
def get_joint_pos(self): # jnt_pos/jnt_pos_name 都可以正常返回,区别在返回的前缀,可测试辨别
|
||||||
return self.__exec_cmd("jnt_pos", "获取轴位置")
|
return self.__exec_cmd("jnt_pos", "获取轴位置")
|
||||||
|
|
||||||
|
@property
|
||||||
def get_axis_vel(self): # jnt_vel/jnt_vel_name 都可以正常返回,区别在返回的前缀,可测试辨别
|
def get_axis_vel(self): # jnt_vel/jnt_vel_name 都可以正常返回,区别在返回的前缀,可测试辨别
|
||||||
return self.__exec_cmd("jnt_vel", "获取轴速度")
|
return self.__exec_cmd("jnt_vel", "获取轴速度")
|
||||||
|
|
||||||
|
@property
|
||||||
def get_axis_trq(self): # jnt_trq/jnt_trq_name 都可以正常返回,区别在返回的前缀,可测试辨别
|
def get_axis_trq(self): # jnt_trq/jnt_trq_name 都可以正常返回,区别在返回的前缀,可测试辨别
|
||||||
return self.__exec_cmd("jnt_trq", "获取轴力矩")
|
return self.__exec_cmd("jnt_trq", "获取轴力矩")
|
||||||
|
|
||||||
|
@property
|
||||||
def reduced_mode_state(self):
|
def reduced_mode_state(self):
|
||||||
return self.__exec_cmd("reduced_mode_state", "获取缩减模式状态")
|
return self.__exec_cmd("reduced_mode_state", "获取缩减模式状态")
|
||||||
|
|
||||||
|
@property
|
||||||
def get_io_state(self, io_list: str): # DO0_0,DI1_3,DO2_5,不能有空格
|
def get_io_state(self, io_list: str): # DO0_0,DI1_3,DO2_5,不能有空格
|
||||||
return self.__exec_cmd(f"io_state:{io_list}", "获取 IO 状态值")
|
return self.__exec_cmd(f"io_state:{io_list}", "获取 IO 状态值")
|
||||||
|
|
||||||
|
@property
|
||||||
def alarm_state(self):
|
def alarm_state(self):
|
||||||
return self.__exec_cmd("alarm_state", "获取报警状态")
|
return self.__exec_cmd("alarm_state", "获取报警状态")
|
||||||
|
|
||||||
|
@property
|
||||||
def collision_alarm_state(self):
|
def collision_alarm_state(self):
|
||||||
return self.__exec_cmd("collision_alarm_state", "获取碰撞检测报警状态")
|
return self.__exec_cmd("collision_alarm_state", "获取碰撞检测报警状态")
|
||||||
|
|
||||||
|
@property
|
||||||
def collision_open_state(self):
|
def collision_open_state(self):
|
||||||
return self.__exec_cmd("collision_open_state", "获取碰撞检测开启状态")
|
return self.__exec_cmd("collision_open_state", "获取碰撞检测开启状态")
|
||||||
|
|
||||||
|
@property
|
||||||
def controller_is_running(self):
|
def controller_is_running(self):
|
||||||
return self.__exec_cmd("controller_is_running", "判断控制器是否开机")
|
return self.__exec_cmd("controller_is_running", "判断控制器是否开机")
|
||||||
|
|
||||||
|
@property
|
||||||
def encoder_low_battery_state(self):
|
def encoder_low_battery_state(self):
|
||||||
return self.__exec_cmd("encoder_low_battery_state", "编码器低电压报警状态")
|
return self.__exec_cmd("encoder_low_battery_state", "编码器低电压报警状态")
|
||||||
|
|
||||||
|
@property
|
||||||
def robot_error_code(self):
|
def robot_error_code(self):
|
||||||
return self.__exec_cmd("robot_error_code", "获取机器人错误码")
|
return self.__exec_cmd("robot_error_code", "获取机器人错误码")
|
||||||
|
|
||||||
|
@property
|
||||||
def get_rl_pause_state(self):
|
def get_rl_pause_state(self):
|
||||||
return self.__exec_cmd("program_full", "获取 RL 的暂停状态")
|
return self.__exec_cmd("program_full", "获取 RL 的暂停状态")
|
||||||
|
|
||||||
|
@property
|
||||||
def program_reset_state(self):
|
def program_reset_state(self):
|
||||||
return self.__exec_cmd("program_reset_state", "获取程序复位状态")
|
return self.__exec_cmd("program_reset_state", "获取程序复位状态")
|
||||||
|
|
||||||
|
@property
|
||||||
def program_speed(self):
|
def program_speed(self):
|
||||||
return self.__exec_cmd("program_speed", "获取程序运行速度")
|
return self.__exec_cmd("program_speed", "获取程序运行速度")
|
||||||
|
|
||||||
|
@property
|
||||||
def robot_is_busy(self):
|
def robot_is_busy(self):
|
||||||
return self.__exec_cmd("robot_is_busy", "获取程序忙碌状态")
|
return self.__exec_cmd("robot_is_busy", "获取程序忙碌状态")
|
||||||
|
|
||||||
|
@property
|
||||||
def robot_is_moving(self):
|
def robot_is_moving(self):
|
||||||
return self.__exec_cmd("robot_is_moving", "获取程序运行状态")
|
return self.__exec_cmd("robot_is_moving", "获取程序运行状态")
|
||||||
|
|
||||||
|
@property
|
||||||
def safe_door_state(self):
|
def safe_door_state(self):
|
||||||
return self.__exec_cmd("safe_door_state", "获取安全门状态")
|
return self.__exec_cmd("safe_door_state", "获取安全门状态")
|
||||||
|
|
||||||
|
@property
|
||||||
def soft_estop_state(self):
|
def soft_estop_state(self):
|
||||||
return self.__exec_cmd("soft_estop_state", "获取软急停状态")
|
return self.__exec_cmd("soft_estop_state", "获取软急停状态")
|
||||||
|
|
||||||
|
@property
|
||||||
def get_cart_vel(self):
|
def get_cart_vel(self):
|
||||||
return self.__exec_cmd("cart_vel", "获取笛卡尔速度")
|
return self.__exec_cmd("cart_vel", "获取笛卡尔速度")
|
||||||
|
|
||||||
|
@property
|
||||||
def get_tcp_pos(self):
|
def get_tcp_pos(self):
|
||||||
return self.__exec_cmd("tcp_pos", "获取 TCP 位姿")
|
return self.__exec_cmd("tcp_pos", "获取 TCP 位姿")
|
||||||
|
|
||||||
|
@property
|
||||||
def get_tcp_vel(self):
|
def get_tcp_vel(self):
|
||||||
return self.__exec_cmd("tcp_vel", "获取 TCP 速度")
|
return self.__exec_cmd("tcp_vel", "获取 TCP 速度")
|
||||||
|
|
||||||
|
@property
|
||||||
def get_tcp_vel_mag(self):
|
def get_tcp_vel_mag(self):
|
||||||
return self.__exec_cmd("tcp_vel_mag", "获取 TCP 合成线速度")
|
return self.__exec_cmd("tcp_vel_mag", "获取 TCP 合成线速度")
|
||||||
|
|
||||||
|
@property
|
||||||
def ext_estop_state(self):
|
def ext_estop_state(self):
|
||||||
return self.__exec_cmd("ext_estop_state", "获取外部轴急停状态")
|
return self.__exec_cmd("ext_estop_state", "获取外部轴急停状态")
|
||||||
|
|
||||||
|
@property
|
||||||
def hand_estop_state(self):
|
def hand_estop_state(self):
|
||||||
return self.__exec_cmd("hand_estop_state", "获取手持急停状态")
|
return self.__exec_cmd("hand_estop_state", "获取手持急停状态")
|
||||||
|
|
||||||
|
@property
|
||||||
def collaboration_state(self): # TBD
|
def collaboration_state(self): # TBD
|
||||||
return self.__exec_cmd("collaboration_state", "获取协作模式状态")
|
return self.__exec_cmd("collaboration_state", "获取协作模式状态")
|
||||||
|
|
||||||
|
Loading…
x
Reference in New Issue
Block a user