2. Descrizione Strutture Dati

2.1. Tipo Struttura di Feedback di Stato del Robot

  1class ROBOT_AUX_STATE(Structure):
  2    _pack_ = 1
  3    _fields_ = [
  4        ("servoId", c_uint8),         # Numero ID driver servo
  5        ("servoErrCode", c_int),     # Codice guasto driver servo
  6        ("servoState", c_int),       # Stato driver servo
  7        ("servoPos", c_double),      # Posizione corrente servo
  8        ("servoVel", c_float),       # Velocità corrente servo
  9        ("servoTorque", c_float),    # Coppia corrente servo
 10    ]
 11
 12class EXT_AXIS_STATUS(Structure):
 13    _pack_ = 1
 14    _fields_ = [
 15        ("pos", c_double),        # Posizione asse di estensione
 16        ("vel", c_double),        # Velocità asse di estensione
 17        ("errorCode", c_int),     # Codice guasto asse di estensione
 18        ("ready", c_uint8),        # Servo pronto
 19        ("inPos", c_uint8),        # Servo in posizione
 20        ("alarm", c_uint8),        # Allarme servo
 21        ("flerr", c_uint8),        # Errore di inseguimento
 22        ("nlimit", c_uint8),       # Limite negativo raggiunto
 23        ("pLimit", c_uint8),       # Limite positivo raggiunto
 24        ("mdbsOffLine", c_uint8),  # Bus 485 driver offline
 25        ("mdbsTimeout", c_uint8),  # Timeout comunicazione 485 tra scheda di controllo e box di controllo
 26        ("homingStatus", c_uint8), # Stato homing asse di estensione
 27    ]
 28
 29class WELDING_BREAKOFF_STATE(Structure):
 30    _pack_ = 1
 31    _fields_ = [
 32        ("breakOffState", c_uint8),        # Stato interruzione saldatura
 33        ("weldArcState", c_uint8),        # Stato interruzione arco di saldatura
 34    ]
 35
 36# ==================== Struttura Completa dello Stato del Robot ====================
 37class RobotStatePkg(Structure):
 38    """
 39    Pacchetto dati di feedback di stato del robot
 40    """
 41    _pack_ = 1
 42    _fields_ = [
 43        # Informazioni intestazione frame
 44        ("frame_head", c_uint16),           # Intestazione frame, concordata come 0x5A5A
 45        ("frame_cnt", c_uint8),             # Conteggio frame, conteggio ciclico 0-255
 46        ("data_len", c_uint16),             # Lunghezza del contenuto dei dati
 47        ("program_state", c_uint8),         # Stato di esecuzione del programma, 1-arrestato; 2-in esecuzione; 3-in pausa
 48        ("robot_state", c_uint8),             # Stato di movimento del robot, 1-arrestato; 2-in movimento; 3-in pausa; 4-trascinamento
 49        ("main_code", c_int),               # Codice guasto principale
 50        ("sub_code", c_int),                # Codice guasto secondario
 51        ("robot_mode", c_uint8),            # Modalità robot, 1-manuale; 0-automatica
 52
 53        # Posizioni e velocità dei giunti
 54        ("jt_cur_pos", c_double * 6),       # Posizioni articolari correnti di 6 assi, unità deg
 55        ("tl_cur_pos", c_double * 6),       # Posizione corrente utensile [x,y,z,rx,ry,rz]
 56        ("flange_cur_pos", c_double * 6),   # Posizione corrente flangia terminale [x,y,z,rx,ry,rz]
 57        ("actual_qd", c_double * 6),        # Velocità correnti di 6 giunti, unità deg/s
 58        ("actual_qdd", c_double * 6),       # Accelerazioni correnti di 6 giunti, unità deg/s^2
 59        ("target_TCP_CmpSpeed", c_double * 2),  # Velocità di comando composita TCP [posizione mm/s, orientamento deg/s]
 60        ("target_TCP_Speed", c_double * 6), # Velocità di comando TCP [x,y,z,rx,ry,rz]
 61        ("actual_TCP_CmpSpeed", c_double * 2),  # Velocità effettiva composita TCP [posizione mm/s, orientamento deg/s]
 62        ("actual_TCP_Speed", c_double * 6), # Velocità effettiva TCP [x,y,z,rx,ry,rz]
 63        ("jt_cur_tor", c_double * 6),       # Coppie correnti di 6 assi, unità N·m
 64
 65        # Sistemi di coordinate utensile e pezzo
 66        ("tool", c_int),                    # Numero del sistema di coordinate utensile applicato
 67        ("user", c_int),                    # Numero del sistema di coordinate pezzo applicato
 68
 69        # I/O digitale
 70        ("cl_dgt_output_h", c_uint8),       # Uscita IO digitale del box di controllo 15-8
 71        ("cl_dgt_output_l", c_uint8),       # Uscita IO digitale del box di controllo 7-0
 72        ("tl_dgt_output_l", c_uint8),       # Uscita IO digitale dell'utensile 7-0, solo bit0-bit1 validi
 73        ("cl_dgt_input_h", c_uint8),        # Ingresso IO digitale del box di controllo 15-8
 74        ("cl_dgt_input_l", c_uint8),        # Ingresso IO digitale del box di controllo 7-0
 75        ("tl_dgt_input_l", c_uint8),        # Ingresso IO digitale dell'utensile 7-0, solo bit0-bit1 validi
 76
 77        # I/O analogico
 78        ("cl_analog_input", c_uint16 * 2),  # Ingresso analogico del box di controllo [0],[1]
 79        ("tl_anglog_input", c_uint16),      # Ingresso analogico dell'utensile
 80
 81        # Sensore di forza/coppia
 82        ("ft_sensor_raw_data", c_double * 6),   # Dati grezzi del sensore di forza/coppia
 83        ("ft_sensor_data", c_double * 6),      # Dati del sensore di forza/coppia
 84        ("ft_sensor_active", c_uint8),          # Stato di attivazione del sensore di forza/coppia
 85
 86        # Segnali di stato
 87        ("EmergencyStop", c_uint8),         # Flag di arresto di emergenza, 0-non premuto, 1-premuto
 88        ("motion_done", c_int),             # Segnale di movimento completato, 1-completato, 0-non completato
 89        ("gripper_motiondone", c_uint8),    # Segnale di movimento della pinza completato, 1-completato, 0-non completato
 90        ("mc_queue_len", c_int),            # Lunghezza della coda dei comandi di movimento
 91        ("collisionState", c_uint8),        # Rilevamento collisione, 1-collisione, 0-nessuna collisione
 92        ("trajectory_pnum", c_int),         # Numero del punto di traiettoria
 93        ("safety_stop0_state", c_uint8),    # Segnale di arresto di sicurezza SI0
 94        ("safety_stop1_state", c_uint8),    # Segnale di arresto di sicurezza SI1
 95
 96        # Informazioni pinza
 97        ("gripper_fault_id", c_uint8),      # Numero pinza guasta
 98        ("gripper_fault", c_uint16),        # Guasto pinza
 99        ("gripper_active", c_uint16),      # Stato di attivazione della pinza
100        ("gripper_position", c_uint8),      # Posizione della pinza
101        ("gripper_speed", c_int8),          # Velocità della pinza
102        ("gripper_current", c_int8),        # Corrente della pinza
103        ("gripper_temp", c_int),            # Temperatura della pinza
104        ("gripper_voltage", c_int),         # Tensione della pinza
105
106        # Stato assi di estensione
107        ("aux_axis_state", ROBOT_AUX_STATE * 25),    # Stato assi di estensione 485 (25)
108        ("extAxisStatus", EXT_AXIS_STATUS * 4), # Stato assi di estensione UDP (4)
109
110        # Stato I/O esteso
111        ("extDIState", c_uint16 * 8),       # Ingresso DI esteso
112        ("extDOState", c_uint16 * 8),       # Uscita DO estesa
113        ("extAIState", c_uint16 * 4),        # Ingresso AI esteso
114        ("extAOState", c_uint16 * 4),        # Uscita AO estesa
115
116        # Stato robot e giunti
117        ("rbtEnableState", c_int),                  # Stato di abilitazione del robot
118        ("jointDriverTorque", c_double * 6),        # Coppia del driver dei giunti del robot
119        ("jointDriverTemperature", c_double * 6),   # Temperatura del driver dei giunti del robot
120
121        # Tempo del robot
122        #("robotTime", c_int * 7),             # Tempo del sistema robot [anno,mese,giorno,ora,minuto,secondo,millisecondo]
123        ("year", ctypes.c_uint16),  # Anno
124        ("mouth", ctypes.c_uint8),  # Mese
125        ("day", ctypes.c_uint8),   # Giorno
126        ("hour", ctypes.c_uint8),   # Ora
127        ("minute", ctypes.c_uint8), # Minuto
128        ("second", ctypes.c_uint8), # Secondo
129        ("millisecond", ctypes.c_uint16), # Millisecondo
130
131        ("softwareUpgradeState", c_int),      # Stato di aggiornamento del software del robot
132        ("endLuaErrCode", c_uint16),          # Stato di esecuzione Lua dell'estremità
133
134        # Uscita analogica
135        ("cl_analog_output", c_uint16 * 2), # Uscita analogica del box di controllo [0],[1]
136        ("tl_analog_output", c_uint16),       # Uscita analogica dell'utensile
137
138        # Pinza rotante
139        ("gripperRotNum", c_float),         # Numero di giri corrente della pinza rotante
140        ("gripperRotSpeed", c_uint8),       # Percentuale di velocità di rotazione corrente della pinza rotante
141        ("gripperRotTorque", c_uint8),      # Percentuale di coppia di rotazione corrente della pinza rotante
142
143        # Stato interruzione saldatura - utilizzo struttura
144        ("weldingBreakOffState", WELDING_BREAKOFF_STATE),  # Stato interruzione saldatura
145
146        # Coppia articolare target
147        ("jt_tgt_tor", c_double * 6),       # Coppia di comando del giunto
148
149        ("smartToolState", c_int),          # Stato del pulsante della maniglia SmartTool
150        ("wideVoltageCtrlBoxTemp", c_float),        # Temperatura del box di controllo wide voltage
151        ("wideVoltageCtrlBoxFanCurrent", c_uint16), # Corrente ventola del box di controllo wide voltage (mA)
152
153        # Valori del sistema di coordinate
154        ("toolCoord", c_double * 6),        # Valori correnti del sistema di coordinate utensile; x,y,z,rx,ry,rz
155        ("wobjCoord", c_double * 6),        # Valori correnti del sistema di coordinate pezzo; x,y,z,rx,ry,rz
156        ("extoolCoord", c_double * 6),      # Valori correnti del sistema di coordinate utensile esterno; x,y,z,rx,ry,rz
157        ("exAxisCoord", c_double * 6),      # Valori correnti del sistema di coordinate assi di estensione; x,y,z,rx,ry,rz
158
159        # Carico
160        ("load", c_double),                 # Massa del carico
161        ("loadCog", c_double * 3),            # Centro di gravità del carico
162
163        # Comandi servo
164        ("lastServoTarget", c_double * 6),  # Ultima posizione target ServoJ nella coda
165        ("servoJCmdNum", c_int),            # Conteggio comandi ServoJ
166
167        # Dati giunto target
168        ("targetJointPos", c_double * 6),   # Posizione di comando di 6 giunti, unità °
169        ("targetJointVel", c_double * 6),   # Velocità di comando di 6 giunti, unità °/s
170        ("targetJointAcc", c_double * 6),   # Accelerazione di comando di 6 giunti, unità °/s2
171        ("targetJointCurrent", c_double * 6), # Corrente di comando di 6 giunti, unità A
172        ("actualJointCurrent", c_double * 6), # Corrente corrente di 6 giunti, unità A
173        ("actualTCPForce", c_double * 6),   # Coppia dell'end-effector del robot Nm; x,y,z,rx,ry,rz
174        ("targetTCPPos", c_double * 6),     # Posizione di comando TCP del robot mm; x,y,z,rx,ry,rz
175
176        ("collisionLevel", c_uint8 * 6),    # Livello di collisione del robot
177        ("speedScaleManual", c_double),     # Percentuale di velocità globale in modalità manuale
178        ("speedScaleAuto", c_double),       # Percentuale di velocità globale in modalità automatica
179        ("luaLineNum", c_int),              # Numero di riga corrente del programma Lua in esecuzione
180        ("abnomalStop", c_uint8),           # 0-nessuna anomalia; 1-anomalia presente
181        ("currentLuaFileName", c_uint8 * 256),  # Nome del programma Lua attualmente in esecuzione
182        ("programTotalLine", c_uint8),      # Numero totale di righe del programma Lua
183        ("safetyBoxSingal", c_uint8 * 6),   # Stato dei pulsanti del box pulsanti del robot
184
185        # Dati saldatura
186        ("weldVoltage", c_double),          # Tensione di saldatura V
187        ("weldCurrent", c_double),          # Corrente di saldatura
188        ("weldTrackVel", c_double),         # Velocità di inseguimento del cordone di saldatura mm/s
189
190        ("tpdException", c_uint8),            # Conteggio di caricamento traiettoria TPD superato, 0-non superato, 1-superato
191        ("alarmRebootRobot", c_uint8),      # Avviso, 1-rilasciare il pulsante di arresto di emergenza e riavviare il box di controllo, 2-anomalia di comunicazione del giunto, riavviare il box di controllo
192        ("modbusMasterConnect", c_uint8),   # bit0-7 corrispondono allo stato di connessione dei master ModbusTCP 0-7
193        ("modbusSlaveConnect", c_uint8),    # Stato di connessione slave ModbusTCP
194        ("btnBoxStopSignal", c_uint8),      # Segnale di arresto di emergenza del box pulsanti
195        ("dragAlarm", c_uint8),             # Avviso di trascinamento
196        ("safetyDoorAlarm", c_uint8),       # Avviso porta di sicurezza
197        ("safetyPlaneAlarm", c_uint8),      # Avviso di ingresso nella parete di sicurezza
198        ("motonAlarm", c_uint8),            # Avviso di movimento
199        ("interfaceAlarm", c_uint8),        # Avviso di ingresso nell'area di interferenza
200        ("udpCmdState", c_int),             # Stato di connessione di comunicazione UDP della porta 20007
201        ("weldReadyState", c_uint8),        # Stato di prontezza della saldatrice
202        ("alarmCheckEmergStopBtn", c_uint8),    # 0-normale; 1-anomalia di comunicazione, verificare se il pulsante di arresto di emergenza è rilasciato
203        ("tsTmCmdComError", c_uint8),       # 0-normale; 1-guasto comunicazione comando coppia
204        ("tsTmStateComError", c_uint8),     # 0-normale; 1-guasto comunicazione stato coppia
205        ("ctrlBoxError", c_int),            # Errore del box di controllo
206        ("safetyDataState", c_uint8),       # Flag di stato dei dati di sicurezza
207        ("forceSensorErrState", c_uint8),   # Guasto timeout connessione sensore di forza
208        ("ctrlOpenLuaErrCode", c_uint8 * 4),  # 4 codici di errore del protocollo aperto del controller periferico
209        ("strangePosFlag", c_uint8),        # Flag di posa singolare attuale
210        ("alarm", c_uint8),                 # Avviso
211        ("driverAlarm", c_uint8),           # Numero asse allarme driver
212        ("aliveSlaveNumError", c_uint8),    # Errore conteggio slave attivi
213        ("slaveComError", c_uint8 * 8),     # Stato errore slave
214        ("cmdPointError", c_uint8),         # Errore punto di comando
215        ("IOError", c_uint8),               # Errore IO
216        ("gripperError", c_uint8),          # Errore pinza
217        ("fileError", c_uint8),             # Errore file
218        ("paraError", c_uint8),             # Errore parametro
219        ("exaxisOutLimitError", c_uint8),   # Errore superamento limite morbido asse esterno
220        ("driverComError", c_uint8 * 6),    # Guasto comunicazione driver
221        ("driverError", c_uint8),           # Numero asse con guasto comunicazione driver
222        ("outSoftLimitError", c_uint8),     # Guasto superamento limite morbido
223        ("axleGenComData", c_uint8 * 130),   # Dati di comunicazione generale assi non periodici
224        ("socketConnTimeout", c_uint8),     # Timeout connessione socket
225        ("socketReadTimeout", c_uint8),     # Timeout lettura socket
226        ("tsWebStateComErr", c_uint8),      # Errore comunicazione stato TS_WEB
227        ("exaxisCoordID", c_uint8),         # ID dell'asse esteso esterno
228        ("check_sum", c_uint16)          # Checksum
229    ]

2.2. Pacchetto Dati Feedback Stato Controller

Nuovo nella versione python: SDK-v2.1.7

Variabile

Significato

program_state

Stato esecuzione programma,1-Fermo; 2-In esecuzione; 3-In pausa

robot_state

Stato movimento robot,1-Fermo; 2-In esecuzione; 3-In pausa; 4-Trascinamento

main_code

Codice errore principale

sub_code

Codice errore secondario

robot_mode

Modalità robot,0-Modalità automatica; 1-Modalità manuale

jt_cur_pos[i]

Posizione corrente giunto, unità deg,i:0~5

tl_cur_pos[i]

Posa corrente utensile, unità deg&mm,i:0~5

flange_cur_pos[i]

Posa corrente flangia terminale, unità deg&mm,i:0~5

actual_qd[i]

Velocità corrente giunti robot, unità deg/s,i:0~5

actual_qdd[i]

Accelerazione corrente giunti robot, unità deg/s^2,i:0~5

target_TCP_CmpSpeed[i]

Velocità sintetica comando TCP robot, unità mm/s&deg/s,i:0~1

target_TCP_Speed[i]

Velocità comando TCP robot, unità mm/s&deg/s,i:0~5

actual_TCP_CmpSpeed[i]

Velocità sintetica effettiva TCP robot, unità mm/s&deg/s,i:0~1

actual_TCP_Speed[i]

Velocità effettiva TCP robot, unità mm/s&deg/s,i:0~5

jt_cur_tor[i]

Coppia corrente, unità N·m ,i:0~5

tool

Numero sistema coordinate utensile applicato

user

Numero sistema coordinate pezzo applicato

cl_dgt_output_h

Uscita IO digitale pannello controllo 15-8

cl_dgt_output_l

Uscita IO digitale pannello controllo 7-0

tl_dgt_output_l

Uscita IO digitale utensile 7-0,solo bit0-bit1 validi

dgt_input_h

Ingresso IO digitale pannello controllo 15-8

cl_dgt_input_l

Ingresso IO digitale pannello controllo 7-0

tl_dgt_input_l

Ingresso IO digitale utensile 7-0,solo bit0-bit1 validi

cl_analog_input[i]

Ingresso analogico pannello controllo,i:0~2

tl_anglog_input

Ingresso analogico utensile

ft_sensor_raw_data

Dati grezzi sensore forza/coppia, unità N&Nm,i:0~5

ft_sensor_data

Dati sensore forza/coppia, unità N&Nm,i:0~5

ft_sensor_active

Stato attivazione sensore forza/coppia,0-Ripristino,1-Attivato

EmergencyStop

Segnale arresto emergenza,0-Arresto emergenza non premuto,1-Arresto emergenza premuto

motion_done

Segnale movimento a posizione,1-A posizione,0-Non a posizione

gripper_motiondone

Segnale completamento movimento pinza,1-Completato,0-Non completato

mc_queue_len

Lunghezza coda comandi movimento

collisionState

Rilevamento collisione,1-Collisione,0-Nessuna collisione

trajectory_pnum

Numero punto traiettoria

safety_stop0_state

Segnale arresto sicurezza SI0

safety_stop1_state

Segnale arresto sicurezza SI1

gripper_fault_id

Numero pinza errore

gripper_fault

Guasto pinza

gripper_active

Stato attivazione pinza,0-Non attivato,1-Attivato

gripper_position

Posizione pinza (percentuale)

gripper_speed

Velocità pinza (percentuale)

gripper_current

Corrente pinza (percentuale)

gripper_tmp

Temperatura pinza, unità ℃

gripper_voltage

Tensione pinza, unità V

auxState.servoId

Asse espansione 485, Numero ID driver servomotore,i:0~3

auxState.servoErrCode

Asse espansione 485, Codice errore driver servomotore,i:0~3

auxState.servoState

Asse espansione 485, Stato driver servomotore,i:0~3

auxState.servoPos

Asse espansione 485, Posizione corrente servomotore,i:0~3

auxState.servoVel

Asse espansione 485, Velocità corrente servomotore,i:0~3

auxState.servoTorque

Asse espansione 485, Coppia corrente servomotore,i:0~3

extAxisStatus[i].pos

Asse espansione UDP, Posizione,i:0~3

extAxisStatus[i].vel

Asse espansione UDP, Velocità,i:0~3

extAxisStatus[i].errorCode

Asse espansione UDP, Codice errore,i:0~3

extAxisStatus[i].ready

Asse espansione UDP, Servomotore pronto,i:0~3

extAxisStatus[i].inPos

Asse espansione UDP, Servomotore a posizione,i:0~3

extAxisStatus[i].alarm

Asse espansione UDP, Allarme servomotore,i:0~3

extAxisStatus[i].flerr

Asse espansione UDP, Errore inseguimento,i:0~3

extAxisStatus[i].nlimit

Asse espansione UDP, A limite negativo,i:0~3

extAxisStatus[i].pLimit

Asse espansione UDP, A limite positivo,i:0~3

extAxisStatus[i].mdbsOffLine

Asse espansione UDP, Bus 485 driver disconnesso

extAxisStatus[i].mdbsTimeout

Asse espansione UDP, Timeout comunicazione 485 scheda controllo-pannello controllo

extAxisStatus[i].homingStatus

Asse espansione UDP, Stato home

extDIState

Stato ingressi digitali espansione

extDOState

Stato uscite digitali espansione

extAIState

Stato ingressi analogici espansione

extAOState

Stato uscite analogiche espansione

rbtEnableState

Stato abilitazione robot

jointDriverTorque

Coppia corrente driver giunti

jointDriverTemperature

Temperatura corrente driver giunti

year

Anno

mouth

Mese

day

Giorno

hour

Ora

minute

Minuto

second

Secondo

millisecond

Millisecondo

softwareUpgradeState

Stato aggiornamento software robot

endLuaErrCode

Stato esecuzione LUA terminale

cl_analog_output[i]

Uscita analogica pannello controllo,i:0~1

tl_analog_output

Uscita analogica utensile

gripperRotNum

Numero rotazioni corrente pinza rotante

gripperRotSpeed

Velocità rotazione percentuale corrente pinza rotante

gripperRotTorque

Coppia rotazione percentuale corrente pinza rotante

weldingBreakOffState

Stato interruzione saldatura

jt_tgt_tor

Coppia comando giunti

smartToolState

Stato pulsante manopola SmartTool

wideVoltageCtrlBoxTemp

Temperatura pannello controllo a tensione ampia

wideVoltageCtrlBoxFanCurrent

Corrente ventilatore pannello controllo a tensione ampia (ma)

toolCoord[i]

Sistema coordinate utensile,i:0~5

wobjCoord[i]

Sistema coordinate pezzo,i:0~5

extoolCoord[i]

Sistema coordinate utensile esterno,i:0~5

exAxisCoord[i]

Sistema coordinate asse espansione,i:0~5

load

Massa carico

loadCog[i]

Baricentro carico,i:0~2

lastServoTarget[i]

Ultima posizione obiettivo ServoJ in coda,i:0~5

servoJCmdNum

Conteggio comandi ServoJ

2.3. Stato Controller Servo

Nuovo nella versione python: SDK-v2.1.3

Variabile

Significato

servoId

Numero ID driver servomotore

servoErrCode

Codice errore driver servomotore

servoState

Stato driver servomotore

servoPos

Posizione corrente servomotore

servoVel

Velocità corrente servomotore

servoTorque

Coppia corrente servomotore

2.4. Stato Asse di Espansione

Nuovo nella versione python: SDK-v2.1.3

Variabile

Significato

pos

Posizione asse di espansione

vel

Velocità asse di espansione

errorCode

Codice errore asse di espansione

ready

Servomotore pronto

inPos

Servomotore a posizione

alarm

Allarme servomotore

flerr

Errore inseguimento

nlimit

A limite negativo

pLimit

A limite positivo

mdbsOffLine

Bus 485 driver disconnesso

mdbsTimeout

Timeout comunicazione 485 scheda controllo-pannello controllo

homingStatus

Stato home asse di espansione

2.5. Stato Interruzione Saldatura

Nuovo nella versione python: SDK-v2.1.3

Variabile

Significato

breakOffState

Stato interruzione saldatura

weldArcState

Stato interruzione arco saldatura

2.6. Esempio di Codice

  1from fairino import Robot
  2# Stabilisce connessione con il controller robot, restituisce un oggetto robot in caso di successo
  3robot = Robot.RPC('192.168.58.2')
  4print("program_state:", robot.robot_state_pkg.program_state)
  5print("robot_state:", robot.robot_state_pkg.robot_state)
  6print("main_code:", robot.robot_state_pkg.main_code)
  7print("sub_code:", robot.robot_state_pkg.sub_code)
  8print("robot_mode:", robot.robot_state_pkg.robot_mode)
  9print("jt_cur_pos0:", robot.robot_state_pkg.jt_cur_pos[0])
 10print("jt_cur_pos1:", robot.robot_state_pkg.jt_cur_pos[1])
 11print("jt_cur_pos2:", robot.robot_state_pkg.jt_cur_pos[2])
 12print("jt_cur_pos3:", robot.robot_state_pkg.jt_cur_pos[3])
 13print("jt_cur_pos4:", robot.robot_state_pkg.jt_cur_pos[4])
 14print("jt_cur_pos5:", robot.robot_state_pkg.jt_cur_pos[5])
 15print("tl_cur_pos0:", robot.robot_state_pkg.tl_cur_pos[0])
 16print("tl_cur_pos1:", robot.robot_state_pkg.tl_cur_pos[1])
 17print("tl_cur_pos2:", robot.robot_state_pkg.tl_cur_pos[2])
 18print("tl_cur_pos3:", robot.robot_state_pkg.tl_cur_pos[3])
 19print("tl_cur_pos4:", robot.robot_state_pkg.tl_cur_pos[4])
 20print("tl_cur_pos5:", robot.robot_state_pkg.tl_cur_pos[5])
 21print("flange_cur_pos0:", robot.robot_state_pkg.flange_cur_pos[0])
 22print("flange_cur_pos1:", robot.robot_state_pkg.flange_cur_pos[1])
 23print("flange_cur_pos2:", robot.robot_state_pkg.flange_cur_pos[2])
 24print("flange_cur_pos3:", robot.robot_state_pkg.flange_cur_pos[3])
 25print("flange_cur_pos4:", robot.robot_state_pkg.flange_cur_pos[4])
 26print("flange_cur_pos5:", robot.robot_state_pkg.flange_cur_pos[5])
 27print("actual_qd0:", robot.robot_state_pkg.actual_qd[0])
 28print("actual_qd1:", robot.robot_state_pkg.actual_qd[1])
 29print("actual_qd2:", robot.robot_state_pkg.actual_qd[2])
 30print("actual_qd3:", robot.robot_state_pkg.actual_qd[3])
 31print("actual_qd4:", robot.robot_state_pkg.actual_qd[4])
 32print("actual_qd5:", robot.robot_state_pkg.actual_qd[5])
 33print("actual_qdd0:", robot.robot_state_pkg.actual_qdd[0])
 34print("actual_qdd1:", robot.robot_state_pkg.actual_qdd[1])
 35print("actual_qdd2:", robot.robot_state_pkg.actual_qdd[2])
 36print("actual_qdd3:", robot.robot_state_pkg.actual_qdd[3])
 37print("actual_qdd4:", robot.robot_state_pkg.actual_qdd[4])
 38print("actual_qdd5:", robot.robot_state_pkg.actual_qdd[5])
 39print("target_TCP_CmpSpeed0:", robot.robot_state_pkg.target_TCP_CmpSpeed[0])
 40print("target_TCP_CmpSpeed1:", robot.robot_state_pkg.target_TCP_CmpSpeed[1])
 41print("target_TCP_Speed0:", robot.robot_state_pkg.target_TCP_Speed[0])
 42print("target_TCP_Speed1:", robot.robot_state_pkg.target_TCP_Speed[1])
 43print("target_TCP_Speed2:", robot.robot_state_pkg.target_TCP_Speed[2])
 44print("target_TCP_Speed3:", robot.robot_state_pkg.target_TCP_Speed[3])
 45print("target_TCP_Speed4:", robot.robot_state_pkg.target_TCP_Speed[4])
 46print("target_TCP_Speed5:", robot.robot_state_pkg.target_TCP_Speed[5])
 47print("actual_TCP_CmpSpeed0:", robot.robot_state_pkg.actual_TCP_CmpSpeed[0])
 48print("actual_TCP_CmpSpeed1:", robot.robot_state_pkg.actual_TCP_CmpSpeed[1])
 49print("actual_TCP_Speed0:", robot.robot_state_pkg.actual_TCP_Speed[0])
 50print("actual_TCP_Speed1:", robot.robot_state_pkg.actual_TCP_Speed[1])
 51print("actual_TCP_Speed2:", robot.robot_state_pkg.actual_TCP_Speed[2])
 52print("actual_TCP_Speed3:", robot.robot_state_pkg.actual_TCP_Speed[3])
 53print("actual_TCP_Speed4:", robot.robot_state_pkg.actual_TCP_Speed[4])
 54print("actual_TCP_Speed5:", robot.robot_state_pkg.actual_TCP_Speed[5])
 55print("jt_cur_tor0:", robot.robot_state_pkg.jt_cur_tor[0])
 56print("jt_cur_tor1:", robot.robot_state_pkg.jt_cur_tor[1])
 57print("jt_cur_tor2:", robot.robot_state_pkg.jt_cur_tor[2])
 58print("jt_cur_tor3:", robot.robot_state_pkg.jt_cur_tor[3])
 59print("jt_cur_tor4:", robot.robot_state_pkg.jt_cur_tor[4])
 60print("jt_cur_tor5:", robot.robot_state_pkg.jt_cur_tor[5])
 61print("tool:", robot.robot_state_pkg.tool)
 62print("user:", robot.robot_state_pkg.user)
 63print("cl_dgt_output_h:", robot.robot_state_pkg.cl_dgt_output_h)
 64print("cl_dgt_output_l:", robot.robot_state_pkg.cl_dgt_output_l)
 65print("tl_dgt_output_l:", robot.robot_state_pkg.tl_dgt_output_l)
 66print("cl_dgt_input_h:", robot.robot_state_pkg.cl_dgt_input_h)
 67print("cl_dgt_input_l:", robot.robot_state_pkg.cl_dgt_input_l)
 68print("tl_dgt_input_l:", robot.robot_state_pkg.tl_dgt_input_l)
 69print("cl_analog_input0:", robot.robot_state_pkg.cl_analog_input[0])
 70print("cl_analog_input1:", robot.robot_state_pkg.cl_analog_input[1])
 71print("tl_anglog_input:", robot.robot_state_pkg.tl_anglog_input)
 72print("ft_sensor_raw_data0:", robot.robot_state_pkg.ft_sensor_raw_data[0])
 73print("ft_sensor_raw_data1:", robot.robot_state_pkg.ft_sensor_raw_data[1])
 74print("ft_sensor_raw_data2:", robot.robot_state_pkg.ft_sensor_raw_data[2])
 75print("ft_sensor_raw_data3:", robot.robot_state_pkg.ft_sensor_raw_data[3])
 76print("ft_sensor_raw_data4:", robot.robot_state_pkg.ft_sensor_raw_data[4])
 77print("ft_sensor_raw_data5:", robot.robot_state_pkg.ft_sensor_raw_data[5])
 78print("ft_sensor_data0:", robot.robot_state_pkg.ft_sensor_data[0])
 79print("ft_sensor_data1:", robot.robot_state_pkg.ft_sensor_data[1])
 80print("ft_sensor_data2:", robot.robot_state_pkg.ft_sensor_data[2])
 81print("ft_sensor_data3:", robot.robot_state_pkg.ft_sensor_data[3])
 82print("ft_sensor_data4:", robot.robot_state_pkg.ft_sensor_data[4])
 83print("ft_sensor_data5:", robot.robot_state_pkg.ft_sensor_data[5])
 84print("ft_sensor_active:", robot.robot_state_pkg.ft_sensor_active)
 85print("EmergencyStop:", robot.robot_state_pkg.EmergencyStop)
 86print("motion_done:", robot.robot_state_pkg.motion_done)
 87print("gripper_motiondone:", robot.robot_state_pkg.gripper_motiondone)
 88print("mc_queue_len:", robot.robot_state_pkg.mc_queue_len)
 89print("collisionState:", robot.robot_state_pkg.collisionState)
 90print("trajectory_pnum:", robot.robot_state_pkg.trajectory_pnum)
 91print("safety_stop0_state:", robot.robot_state_pkg.safety_stop0_state)
 92print("safety_stop1_state:", robot.robot_state_pkg.safety_stop1_state)
 93print("gripper_fault_id:", robot.robot_state_pkg.gripper_fault_id)
 94print("gripper_fault:", robot.robot_state_pkg.gripper_fault)
 95print("gripper_active:", robot.robot_state_pkg.gripper_active)
 96print("gripper_position:", robot.robot_state_pkg.gripper_position)
 97print("gripper_speed:", robot.robot_state_pkg.gripper_speed)
 98print("gripper_current:", robot.robot_state_pkg.gripper_current)
 99print("gripper_tmp:", robot.robot_state_pkg.gripper_tmp)
100print("gripper_voltage:", robot.robot_state_pkg.gripper_voltage)
101print("auxState.servoId:", robot.robot_state_pkg.auxState.servoId)
102print("auxState.servoErrCode:", robot.robot_state_pkg.auxState.servoErrCode)
103print("auxState.servoState:", robot.robot_state_pkg.auxState.servoState)
104print("auxState.servoPos:", robot.robot_state_pkg.auxState.servoPos)
105print("auxState.servoVel:", robot.robot_state_pkg.auxState.servoVel)
106print("auxState.servoTorque:", robot.robot_state_pkg.auxState.servoTorque)
107for i in range(4):
108    print("extAxisStatus.pos:", i,robot.robot_state_pkg.extAxisStatus[i].pos)
109    print("extAxisStatus.vel:", i,robot.robot_state_pkg.extAxisStatus[i].vel)
110    print("extAxisStatus.errorCode:", i,robot.robot_state_pkg.extAxisStatus[i].errorCode)
111    print("extAxisStatus.ready:", i,robot.robot_state_pkg.extAxisStatus[i].ready)
112    print("extAxisStatus.inPos:", i,robot.robot_state_pkg.extAxisStatus[i].inPos)
113    print("extAxisStatus.alarm:", i,robot.robot_state_pkg.extAxisStatus[i].alarm)
114    print("extAxisStatus.flerr:", i,robot.robot_state_pkg.extAxisStatus[i].flerr)
115    print("extAxisStatus.nlimit:", i,robot.robot_state_pkg.extAxisStatus[i].nlimit)
116    print("extAxisStatus.pLimit:", i,robot.robot_state_pkg.extAxisStatus[i].pLimit)
117    print("extAxisStatus.mdbsOffLine:", i,robot.robot_state_pkg.extAxisStatus[i].mdbsOffLine)
118    print("extAxisStatus.mdbsTimeout:", i,robot.robot_state_pkg.extAxisStatus[i].mdbsTimeout)
119    print("extAxisStatus.homingStatus:", i,robot.robot_state_pkg.extAxisStatus[i].homingStatus)
120for i in range(8):
121    print("extDIState:",i, robot.robot_state_pkg.extDIState[i])
122    print("extDOState:", i,robot.robot_state_pkg.extDOState[i])
123for i in range(4):
124    print("extAIState:", i,robot.robot_state_pkg.extAIState[i])
125    print("extAOState:", robot.robot_state_pkg.extAOState[i])
126print("rbtEnableState:", robot.robot_state_pkg.rbtEnableState)
127print("jointDriverTorque0:", robot.robot_state_pkg.jointDriverTorque[0])
128print("jointDriverTorque1:", robot.robot_state_pkg.jointDriverTorque[1])
129print("jointDriverTorque2:", robot.robot_state_pkg.jointDriverTorque[2])
130print("jointDriverTorque3:", robot.robot_state_pkg.jointDriverTorque[3])
131print("jointDriverTorque4:", robot.robot_state_pkg.jointDriverTorque[4])
132print("jointDriverTorque5:", robot.robot_state_pkg.jointDriverTorque[5])
133print("jointDriverTemperature:", robot.robot_state_pkg.jointDriverTemperature[0])
134print("jointDriverTemperature:", robot.robot_state_pkg.jointDriverTemperature[1])
135print("jointDriverTemperature:", robot.robot_state_pkg.jointDriverTemperature[2])
136print("jointDriverTemperature:", robot.robot_state_pkg.jointDriverTemperature[3])
137print("jointDriverTemperature:", robot.robot_state_pkg.jointDriverTemperature[4])
138print("jointDriverTemperature:", robot.robot_state_pkg.jointDriverTemperature[5])
139print("year:", robot.robot_state_pkg.year)
140print("mouth:", robot.robot_state_pkg.mouth)
141print("day:", robot.robot_state_pkg.day)
142print("hour:", robot.robot_state_pkg.hour)
143print("minute:", robot.robot_state_pkg.minute)
144print("second:", robot.robot_state_pkg.second)
145print("millisecond:", robot.robot_state_pkg.millisecond)
146print("softwareUpgradeState:", robot.robot_state_pkg.softwareUpgradeState)
147print("endLuaErrCode:", robot.robot_state_pkg.endLuaErrCode)
148print("cl_analog_output[0]:", robot.robot_state_pkg.cl_analog_output[0])
149print("cl_analog_output[1]:", robot.robot_state_pkg.cl_analog_output[1])
150print("tl_analog_output:", robot.robot_state_pkg.tl_analog_output)
151print("gripperRotNum:", robot.robot_state_pkg.gripperRotNum)
152print("gripperRotSpeed:", robot.robot_state_pkg.gripperRotSpeed)
153print("gripperRotTorque:", robot.robot_state_pkg.gripperRotTorque)
154print("jt_tgt_tor:", robot.robot_state_pkg.jt_tgt_tor)
155print("smartToolState:", robot.robot_state_pkg.smartToolState)
156print("wideVoltageCtrlBoxTemp:", robot.robot_state_pkg.wideVoltageCtrlBoxTemp)
157print("wideVoltageCtrlBoxFanCurrent:", robot.robot_state_pkg.wideVoltageCtrlBoxFanCurrent)
158print("toolCoord0:", robot.robot_state_pkg.toolCoord[0])
159print("toolCoord1:", robot.robot_state_pkg.toolCoord[1])
160print("toolCoord2:", robot.robot_state_pkg.toolCoord[2])
161print("toolCoord3:", robot.robot_state_pkg.toolCoord[3])
162print("toolCoord4:", robot.robot_state_pkg.toolCoord[4])
163print("toolCoord5:", robot.robot_state_pkg.toolCoord[5])
164print("wobjCoord0:", robot.robot_state_pkg.wobjCoord[0])
165print("wobjCoord1:", robot.robot_state_pkg.wobjCoord[1])
166print("wobjCoord2:", robot.robot_state_pkg.wobjCoord[2])
167print("wobjCoord3:", robot.robot_state_pkg.wobjCoord[3])
168print("wobjCoord4:", robot.robot_state_pkg.wobjCoord[4])
169print("wobjCoord5:", robot.robot_state_pkg.wobjCoord[5])
170print("extoolCoord0:", robot.robot_state_pkg.extoolCoord[0])
171print("extoolCoord1:", robot.robot_state_pkg.extoolCoord[1])
172print("extoolCoord2:", robot.robot_state_pkg.extoolCoord[2])
173print("extoolCoord3:", robot.robot_state_pkg.extoolCoord[3])
174print("extoolCoord4:", robot.robot_state_pkg.extoolCoord[4])
175print("extoolCoord5:", robot.robot_state_pkg.extoolCoord[5])
176print("exAxisCoord0:", robot.robot_state_pkg.exAxisCoord[0])
177print("exAxisCoord1:", robot.robot_state_pkg.exAxisCoord[1])
178print("exAxisCoord2:", robot.robot_state_pkg.exAxisCoord[2])
179print("exAxisCoord3:", robot.robot_state_pkg.exAxisCoord[3])
180print("exAxisCoord4:", robot.robot_state_pkg.exAxisCoord[4])
181print("exAxisCoord5:", robot.robot_state_pkg.exAxisCoord[5])
182print("load:", robot.robot_state_pkg.load)
183print("loadCog0:", robot.robot_state_pkg.loadCog[0])
184print("loadCog1:", robot.robot_state_pkg.loadCog[1])
185print("loadCog2:", robot.robot_state_pkg.loadCog[2])
186print("lastServoTarget0:", robot.robot_state_pkg.lastServoTarget[0])
187print("lastServoTarget1:", robot.robot_state_pkg.lastServoTarget[1])
188print("lastServoTarget2:", robot.robot_state_pkg.lastServoTarget[2])
189print("lastServoTarget3:", robot.robot_state_pkg.lastServoTarget[3])
190print("lastServoTarget4:", robot.robot_state_pkg.lastServoTarget[4])
191print("lastServoTarget5:", robot.robot_state_pkg.lastServoTarget[5])
192print("servoJCmdNum:", robot.robot_state_pkg.servoJCcmdNum)

2.7. Tipo di Enumerazione dell’Elenco di Configurazione del Feedback di Stato del Robot

  1# ==================== Enumerazione Elenco di Configurazione RobotState ====================
  2class RobotState(enum.Enum):
  3    """Enumerazione del tipo di stato CNDE"""
  4    FrameHead = 0
  5    FrameCnt = 1
  6    DataLen = 2
  7    ProgramState = 3
  8    RobotState = 4
  9    MainCode = 5
 10    SubCode = 6
 11    RobotMode = 7
 12    JointCurPos = 8
 13    ToolCurPos = 9
 14    FlangeCurPos = 10
 15    ActualJointVel = 11
 16    ActualJointAcc = 12
 17    TargetTCPCmpSpeed = 13
 18    TargetTCPSpeed = 14
 19    ActualTCPCmpSpeed = 15
 20    ActualTCPSpeed = 16
 21    ActualJointTorque = 17
 22    Tool = 18
 23    User = 19
 24    ClDgtOutputH = 20
 25    ClDgtOutputL = 21
 26    TlDgtOutputL = 22
 27    ClDgtInputH = 23
 28    ClDgtInputL = 24
 29    TlDgtInputL = 25
 30    ClAnalogInput = 26
 31    TlAnglogInput = 27
 32    FtSensorRawData = 28
 33    FtSensorData = 29
 34    FtSensorActive = 30
 35    EmergencyStop = 31
 36    MotionDone = 32
 37    GripperMotiondone = 33
 38    McQueueLen = 34
 39    CollisionState = 35
 40    TrajectoryPnum = 36
 41    SafetyStop0State = 37
 42    SafetyStop1State = 38
 43    GripperFaultId = 39
 44    GripperFault = 40
 45    GripperActive = 41
 46    GripperPosition = 42
 47    GripperSpeed = 43
 48    GripperCurrent = 44
 49    GripperTemp = 45
 50    GripperVoltage = 46
 51    AuxState = 47
 52    ExtAxisStatus = 48
 53    ExtDIState = 49
 54    ExtDOState = 50
 55    ExtAIState = 51
 56    ExtAOState = 52
 57    RbtEnableState = 53
 58    JointDriverTorque = 54
 59    JointDriverTemperature = 55
 60    RobotTime = 56
 61    SoftwareUpgradeState = 57
 62    EndLuaErrCode = 58
 63    ClAnalogOutput = 59
 64    TlAnalogOutput = 60
 65    GripperRotNum = 61
 66    GripperRotSpeed = 62
 67    GripperRotTorque = 63
 68    WeldingBreakOffState = 64
 69    TargetJointTorque = 65
 70    SmartToolState = 66
 71    WideVoltageCtrlBoxTemp = 67
 72    WideVoltageCtrlBoxFanCurrent = 68
 73    ToolCoord = 69
 74    WobjCoord = 70
 75    ExtoolCoord = 71
 76    ExAxisCoord = 72
 77    Load = 73
 78    LoadCog = 74
 79    LastServoTarget = 75
 80    ServoJCmdNum = 76
 81    TargetJointPos = 77
 82    TargetJointVel = 78
 83    TargetJointAcc = 79
 84    TargetJointCurrent = 80
 85    ActualJointCurrent = 81
 86    ActualTCPForce = 82
 87    TargetTCPPos = 83
 88    CollisionLevel = 84
 89    SpeedScaleManual = 85
 90    SpeedScaleAuto = 86
 91    LuaLineNum = 87
 92    AbnomalStop = 88
 93    CurrentLuaFileName = 89
 94    ProgramTotalLine = 90
 95    SafetyBoxSingal = 91
 96    WeldVoltage = 92
 97    WeldCurrent = 93
 98    WeldTrackVel = 94
 99    TpdException = 95
100    AlarmRebootRobot = 96
101    ModbusMasterConnect = 97
102    ModbusSlaveConnect = 98
103    BtnBoxStopSignal = 99
104    DragAlarm = 100
105    SafetyDoorAlarm = 101
106    SafetyPlaneAlarm = 102
107    MotonAlarm = 103
108    InterfaceAlarm = 104
109    UdpCmdState = 105
110    WeldReadyState = 106
111    AlarmCheckEmergStopBtn = 107
112    TsTmCmdComError = 108
113    TsTmStateComError = 109
114    CtrlBoxError = 110
115    SafetyDataState = 111
116    ForceSensorErrState = 112
117    CtrlOpenLuaErrCode = 113
118    StrangePosFlag = 114
119    Alarm = 115
120    DriverAlarm = 116
121    AliveSlaveNumError = 117
122    SlaveComError = 118
123    CmdPointError = 119
124    IOError = 120
125    GripperError = 121
126    FileError = 122
127    ParaError = 123
128    ExaxisOutLimitError = 124
129    DriverComError = 125
130    DriverError = 126
131    OutSoftLimitError = 127
132    AxleGenComData = 128
133    SocketConnTimeout = 129
134    SocketReadTimeout = 130
135    TsWebStateComErr = 131
136    exaxisCoordID = 132
137    CheckSum = 133