2. Datenstrukturbeschreibung
2.1. Controller-Statusrückmeldungs-Datenpaket
Neu in Version Python: SDK-v2.1.7
Variable |
Bedeutung |
|---|---|
program_state |
Programmausführungsstatus: 1 - gestoppt; 2 - läuft; 3 - pausiert |
robot_state |
Roboterbewegungsstatus: 1 - gestoppt; 2 - läuft; 3 - pausiert; 4 - Führung (Drag) |
main_code |
Hauptfehlercode |
sub_code |
Unterfehlercode |
robot_mode |
Robotermodus: 0 - Automatikmodus; 1 - Handmodus |
jt_cur_pos[i] |
Aktuelle Gelenkposition, Einheit [°], i:0~5 |
tl_cur_pos[i] |
Aktuelle Werkzeugpose (TCP), Einheiten [° & mm], i:0~5 |
flange_cur_pos[i] |
Aktuelle Pose des Endflansches, Einheiten [° & mm], i:0~5 |
actual_qd[i] |
Aktuelle Gelenkgeschwindigkeit des Roboters, Einheit [°/s], i:0~5 |
actual_qdd[i] |
Aktuelle Gelenkbeschleunigung des Roboters, Einheit [°/s²], i:0~5 |
target_TCP_CmpSpeed[i] |
Befohlene TCP-Resultierende-Geschwindigkeit, Einheiten [mm/s & °/s], i:0~1 |
target_TCP_Speed[i] |
Befohlene TCP-Geschwindigkeit (Komponenten), Einheiten [mm/s & °/s], i:0~5 |
actual_TCP_CmpSpeed[i] |
Tatsächliche TCP-Resultierende-Geschwindigkeit, Einheiten [mm/s & °/s], i:0~1 |
actual_TCP_Speed[i] |
Tatsächliche TCP-Geschwindigkeit (Komponenten), Einheiten [mm/s & °/s], i:0~5 |
jt_cur_tor[i] |
Aktuelles Gelenkmoment, Einheit [Nm], i:0~5 |
tool |
Nummer des verwendeten Werkzeugkoordinatensystems |
user |
Nummer des verwendeten Werkstückkoordinatensystems |
cl_dgt_output_h |
Digitalausgänge des Steuerkastens (Bits 15-8) |
cl_dgt_output_l |
Digitalausgänge des Steuerkastens (Bits 7-0) |
tl_dgt_output_l |
Digitalausgänge des Werkzeugs (Bits 7-0, nur Bit0-Bit1 gültig) |
dgt_input_h |
Digitaleingänge des Steuerkastens (Bits 15-8) |
cl_dgt_input_l |
Digitaleingänge des Steuerkastens (Bits 7-0) |
tl_dgt_input_l |
Digitaleingänge des Werkzeugs (Bits 7-0, nur Bit0-Bit1 gültig) |
cl_analog_input[i] |
Analogeingänge des Steuerkastens, i:0~2 |
tl_anglog_input |
Analogeingang des Werkzeugs |
ft_sensor_raw_data |
Rohdaten des Kraft-/Momentensensors, Einheiten [N & Nm], i:0~5 |
ft_sensor_data |
Verarbeitete Daten des Kraft-/Momentensensors, Einheiten [N & Nm], i:0~5 |
ft_sensor_active |
Aktivierungsstatus des Kraft-/Momentensensors: 0 - zurückgesetzt, 1 - aktiviert |
EmergencyStop |
Not-Halt-Status: 0 - Not-Halt nicht betätigt, 1 - Not-Halt betätigt |
motion_done |
Bewegungsabschluss-Signal: 1 - abgeschlossen, 0 - nicht abgeschlossen |
gripper_motiondone |
Greiferbewegungsabschluss-Signal: 1 - abgeschlossen, 0 - nicht abgeschlossen |
mc_queue_len |
Länge der Bewegungsbefehlswarteschlange |
collisionState |
Kollisionserkennung: 1 - Kollision, 0 - keine Kollision |
trajectory_pnum |
Trajektorienpunktnummer |
safety_stop0_state |
Sicherheitsstopp-Signal SI0 |
safety_stop1_state |
Sicherheitsstopp-Signal SI1 |
gripper_fault_id |
Nummer des fehlerhaften Greifers |
gripper_fault |
Greiferfehler |
gripper_active |
Greifer-Aktivierungsstatus: 0 - nicht aktiviert, 1 - aktiviert |
gripper_position |
Greiferposition (Prozent) |
gripper_speed |
Greifergeschwindigkeit (Prozent) |
gripper_current |
Greiferstrom (Prozent) |
gripper_tmp |
Greifertemperatur, Einheit [°C] |
gripper_voltage |
Greiferspannung, Einheit [V] |
auxState.servoId |
485-Erweiterungsachse: Servoantriebs-ID, i:0~3 |
auxState.servoErrCode |
485-Erweiterungsachse: Fehlercode des Servoantriebs, i:0~3 |
auxState.servoState |
485-Erweiterungsachse: Status des Servoantriebs, i:0~3 |
auxState.servoPos |
485-Erweiterungsachse: Aktuelle Servoposition, i:0~3 |
auxState.servoVel |
485-Erweiterungsachse: Aktuelle Servogeschwindigkeit, i:0~3 |
auxState.servoTorque |
485-Erweiterungsachse: Aktuelles Servodrehmoment, i:0~3 |
extAxisStatus[i].pos |
UDP-Erweiterungsachse: Position, i:0~3 |
extAxisStatus[i].vel |
UDP-Erweiterungsachse: Geschwindigkeit, i:0~3 |
extAxisStatus[i].errorCode |
UDP-Erweiterungsachse: Fehlercode, i:0~3 |
extAxisStatus[i].ready |
UDP-Erweiterungsachse: Servo bereit, i:0~3 |
extAxisStatus[i].inPos |
UDP-Erweiterungsachse: Servo in Position, i:0~3 |
extAxisStatus[i].alarm |
UDP-Erweiterungsachse: Servo-Alarm, i:0~3 |
extAxisStatus[i].flerr |
UDP-Erweiterungsachse: Folgefhler, i:0~3 |
extAxisStatus[i].nlimit |
UDP-Erweiterungsachse: Negativer Endschalter erreicht, i:0~3 |
extAxisStatus[i].pLimit |
UDP-Erweiterungsachse: Positiver Endschalter erreicht, i:0~3 |
extAxisStatus[i].mdbsOffLine |
UDP-Erweiterungsachse: Antriebs-485-Bus offline |
extAxisStatus[i].mdbsTimeout |
UDP-Erweiterungsachse: 485-Kommunikation zwischen Steuerkarte und Steuerkasten Zeitüberschreitung |
extAxisStatus[i].homingStatus |
UDP-Erweiterungsachse: Referenzfahrt-Status |
extDIState |
Erweiterter Digitaleingangsstatus |
extDOState |
Erweiterter Digitalausgangsstatus |
extAIState |
Erweiterter Analogeingangsstatus |
extAOState |
Erweiterter Analogausgangsstatus |
rbtEnableState |
Roboter-Aktivierungsstatus (Enable) |
jointDriverTorque |
Aktuelles Drehmoment der Gelenkantriebe |
jointDriverTemperature |
Aktuelle Temperatur der Gelenkantriebe |
year |
Jahr |
mouth |
Monat |
day |
Tag |
hour |
Stunde |
minute |
Minute |
second |
Sekunde |
millisecond |
Millisekunde |
softwareUpgradeState |
Status des Roboter-Software-Upgrades |
endLuaErrCode |
Ausführungsstatus des Endeffektor-LUA-Skripts |
cl_analog_output[i] |
Analogausgänge des Steuerkastens, i:0~1 |
tl_analog_output |
Analogausgang des Werkzeugs |
gripperRotNum |
Aktuelle Rotationsanzahl des Rotationsgreifers |
gripperRotSpeed |
Aktuelle Rotationsgeschwindigkeit des Rotationsgreifers (Prozent) |
gripperRotTorque |
Aktuelles Rotationsdrehmoment des Rotationsgreifers (Prozent) |
weldingBreakOffState |
Schweißunterbrechungsstatus |
jt_tgt_tor |
Befehls-Gelenkmoment |
smartToolState |
SmartTool-Griff Tastenstatus |
wideVoltageCtrlBoxTemp |
Temperatur des Weitspannungs-Steuerkastens |
wideVoltageCtrlBoxFanCurrent |
Lüfterstrom des Weitspannungs-Steuerkastens (mA) |
toolCoord[i] |
Werkzeugkoordinatensystem, i:0~5 |
wobjCoord[i] |
Werkstückkoordinatensystem, i:0~5 |
extoolCoord[i] |
Externes Werkzeugkoordinatensystem, i:0~5 |
exAxisCoord[i] |
Erweiterungsachsen-Koordinatensystem, i:0~5 |
load |
Lastmasse |
loadCog[i] |
Lastschwerpunkt, i:0~2 |
lastServoTarget[i] |
Letzte ServoJ-Zielposition in der Warteschlange, i:0~5 |
servoJCmdNum |
ServoJ-Befehlszähler |
2.2. Servocontroller-Status
Neu in Version Python: SDK-v2.1.3
Variable |
Bedeutung |
|---|---|
servoId |
Servoantriebs-ID-Nummer |
servoErrCode |
Fehlercode des Servoantriebs |
servoState |
Status des Servoantriebs |
servoPos |
Aktuelle Servoposition |
servoVel |
Aktuelle Servogeschwindigkeit |
servoTorque |
Aktuelles Servodrehmoment |
2.3. Erweiterungsachsen-Status
Neu in Version Python: SDK-v2.1.3
Variable |
Bedeutung |
|---|---|
pos |
Position der Erweiterungsachse |
vel |
Geschwindigkeit der Erweiterungsachse |
errorCode |
Fehlercode der Erweiterungsachse |
ready |
Servo bereit |
inPos |
Servo in Position |
alarm |
Servo-Alarm |
flerr |
Folgefehler |
nlimit |
Negativer Endschalter erreicht |
pLimit |
Positiver Endschalter erreicht |
mdbsOffLine |
Antriebs-485-Bus offline |
mdbsTimeout |
485-Kommunikation zwischen Steuerkarte und Steuerkasten Zeitüberschreitung |
homingStatus |
Status der Referenzfahrt der Erweiterungsachse |
2.4. Schweißunterbrechungsstatus
Neu in Version Python: SDK-v2.1.3
Variable |
Bedeutung |
|---|---|
breakOffState |
Schweißunterbrechungsstatus |
weldArcState |
Lichtbogenunterbrechungsstatus beim Schweißen |
2.5. Codebeispiel
1from fairino import Robot
2# Verbindung zur Robotersteuerung herstellen, bei Erfolg wird ein Roboterobjekt zurückgegeben
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:", i, 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.servoJCmdNum)