Skip to content

Commit 923683c

Browse files
committed
Version 0.2
Features: - combined_axes_error - get_board_temperature - get_motor_temperature Fixes: - wait_for_kinematics_ready now also checks the axes states - fix comment in relative_move example
1 parent d593109 commit 923683c

11 files changed

+5018
-4537
lines changed

README.md

+1
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,7 @@ Python package to interface an igus Robot Control via the CRI protocol.
2222
- Upload
2323
- Start / Pause / Stop
2424
- CAN Bridge
25+
- Get Board and Motor Temperature (only board supported by ReBeL)
2526

2627
# Getting Started
2728
## Installation

cri_lib/cri_controller.py

+71-12
Original file line numberDiff line numberDiff line change
@@ -26,6 +26,7 @@ class CRIController:
2626

2727
class MotionType(Enum):
2828
"""Robot Motion Type for Jogging"""
29+
2930
Joint = "Joint"
3031
CartBase = "CartBase"
3132
CartTool = "CartTool"
@@ -573,7 +574,9 @@ def wait_for_kinematics_ready(self, timeout: float | None = 30) -> bool:
573574
new_timeout = timeout
574575
while new_timeout > 0.0:
575576
self.wait_for_status_update(timeout=new_timeout)
576-
if self.robot_state.kinematics_state == KinematicsState.NO_ERROR:
577+
if (self.robot_state.kinematics_state == KinematicsState.NO_ERROR) and (
578+
self.robot_state.combined_axes_error == "NoError"
579+
):
577580
return True
578581

579582
new_timeout = timeout - (time() - start_time)
@@ -1124,8 +1127,8 @@ def set_global_signal(self, id: int, value: bool):
11241127
else:
11251128
return False
11261129

1127-
def load_programm(self, program_name:str) -> bool:
1128-
""" Load a program file from disk into the robot controller
1130+
def load_programm(self, program_name: str) -> bool:
1131+
"""Load a program file from disk into the robot controller
11291132
11301133
Parameters
11311134
----------
@@ -1152,9 +1155,9 @@ def load_programm(self, program_name:str) -> bool:
11521155
return True
11531156
else:
11541157
return False
1155-
1156-
def load_logic_programm(self, program_name:str) -> bool:
1157-
""" Load a logic program file from disk into the robot controller
1158+
1159+
def load_logic_programm(self, program_name: str) -> bool:
1160+
"""Load a logic program file from disk into the robot controller
11581161
11591162
Parameters
11601163
----------
@@ -1208,7 +1211,7 @@ def start_programm(self) -> bool:
12081211

12091212
def stop_programm(self) -> bool:
12101213
"""Stop currently running Program
1211-
1214+
12121215
Returns
12131216
-------
12141217
bool
@@ -1232,7 +1235,7 @@ def stop_programm(self) -> bool:
12321235

12331236
def pause_programm(self) -> bool:
12341237
"""Pause currently running Program
1235-
1238+
12361239
Returns
12371240
-------
12381241
bool
@@ -1303,7 +1306,7 @@ def upload_file(self, path: str | Path, target_directory: str) -> bool:
13031306

13041307
command = "CMD UploadFileFinish"
13051308

1306-
if self._send_command(command, True) is None:
1309+
if self._send_command(command, True) is None:
13071310
return False
13081311

13091312
def enable_can_bridge(self, enabled: bool) -> None:
@@ -1337,8 +1340,10 @@ def can_send(self, msg_id: int, length: int, data: bytearray) -> None:
13371340
if not self.can_mode:
13381341
logging.debug("can_send: CAN mode not enabled")
13391342
return
1340-
1341-
command = f"CANBridge Msg ID {msg_id} Len {length} Data " + " ".join([str(int(i)) for i in data])
1343+
1344+
command = f"CANBridge Msg ID {msg_id} Len {length} Data " + " ".join(
1345+
[str(int(i)) for i in data]
1346+
)
13421347

13431348
self._send_command(command)
13441349

@@ -1360,5 +1365,59 @@ def can_receive(
13601365
item = self.can_queue.get(blocking, timeout)
13611366
except Empty:
13621367
return None
1368+
1369+
return item
1370+
1371+
def get_board_temperatures(self, blocking: bool = True, timeout: float | None = None) -> bool:
1372+
"""Receive motor controller PCB temperatures and save in robot state
1373+
1374+
Parameters
1375+
----------
1376+
blocking: bool
1377+
wait for response, always returns True if not waiting
1378+
1379+
timeout: float | None
1380+
timeout for waiting in seconds or None for infinite waiting
1381+
"""
1382+
if (
1383+
self._send_command("SYSTEM GetBoardTemp", True, "info_boardtemp")
1384+
is not None
1385+
):
1386+
if (
1387+
error_msg := self._wait_for_answer(
1388+
"info_boardtemp", timeout=self.DEFAULT_ANSWER_TIMEOUT
1389+
)
1390+
) is not None:
1391+
logging.debug("Error in GetBoardTemp command: %s", error_msg)
1392+
return False
1393+
else:
1394+
return True
1395+
else:
1396+
return False
13631397

1364-
return item
1398+
def get_motor_temperatures(self, blocking: bool = True, timeout: float | None = None) -> bool:
1399+
"""Receive motor temperatures and save in robot state
1400+
1401+
Parameters
1402+
----------
1403+
blocking: bool
1404+
wait for response, always returns True if not waiting
1405+
1406+
timeout: float | None
1407+
timeout for waiting in seconds or None for infinite waiting
1408+
"""
1409+
if (
1410+
self._send_command("SYSTEM GetMotorTemp", True, "info_motortemp")
1411+
is not None
1412+
):
1413+
if (
1414+
error_msg := self._wait_for_answer(
1415+
"info_motortemp", timeout=self.DEFAULT_ANSWER_TIMEOUT
1416+
)
1417+
) is not None:
1418+
logging.debug("Error in GetMotorTemp command: %s", error_msg)
1419+
return False
1420+
else:
1421+
return True
1422+
else:
1423+
return False

cri_lib/cri_protocol_parser.py

+18-2
Original file line numberDiff line numberDiff line change
@@ -216,11 +216,13 @@ def _parse_status(self, parameters: list[str]) -> None:
216216
segment_start_idx += 17
217217

218218
case "ERROR":
219-
# TODO: error state string
220219
errors = []
220+
self.robot_state.combined_axes_error = parameters[
221+
segment_start_idx + 1
222+
]
221223
for axis_idx in range(16):
222224
value_int = int(
223-
parameters[segment_start_idx + 2 + axis_idx], base=16
225+
parameters[segment_start_idx + 2 + axis_idx], base=10
224226
)
225227
error_bits = []
226228
for i in range(8):
@@ -576,6 +578,20 @@ def _parse_info(self, parameters: list[str]) -> None:
576578
self.robot_state.referencing_state = ref_state
577579

578580
return "info_referencing"
581+
elif parameters[0] == "BoardTemp":
582+
temperatures = [float(param) for param in parameters[1:]]
583+
584+
with self.robot_state_lock:
585+
self.robot_state.board_temps = temperatures
586+
587+
return "info_boardtemp"
588+
elif parameters[0] == "MotorTemp":
589+
temperatures = [float(param) for param in parameters[1:]]
590+
591+
with self.robot_state_lock:
592+
self.robot_state.motor_temps = temperatures
593+
594+
return "info_motortemp"
579595
else:
580596
return None
581597

cri_lib/robot_state.py

+9
Original file line numberDiff line numberDiff line change
@@ -291,6 +291,9 @@ class RobotState:
291291
)
292292
"""error states of individual axes"""
293293

294+
combined_axes_error: str = "_not_ready"
295+
"""combined error state of all axes as string"""
296+
294297
cycle_time: float = 0.0
295298
"""cycle time of robot control loop"""
296299

@@ -326,3 +329,9 @@ class RobotState:
326329

327330
referencing_state: ReferencingState = field(default_factory=ReferencingState)
328331
"""individual referencing state of all axes"""
332+
333+
board_temps: list[float] = field(default_factory=lambda: [0.0] * 16)
334+
"""Temperatures of motor controller PCBs"""
335+
336+
motor_temps: list[float] = field(default_factory=lambda: [0.0] * 16)
337+
"""Temperatures of motors"""

docs/cri_lib.html

+1-1
Original file line numberDiff line numberDiff line change
@@ -110,7 +110,7 @@ <h2 id="usage">Usage</h2>
110110
<h3 id="typical-procedure">Typical procedure</h3>
111111

112112
<ol>
113-
<li>Connect to iRC: <code>CRIController.connect(...)</code> Default IP is <code>192.168.3.11</code> with port <code>3921</code>. For using the simulation in the iRC desktop software, connect to <code>127.0.0.1</code>, most of the time the port in the simulation is <code>3921</code>, but can be different. Have a look at the log if you are unable to connect. Check whether connection was successfull via the returned bool.</li>
113+
<li>Connect to iRC: <code>CRIController.connect(...)</code> Default IP is <code>192.168.3.11</code> with port <code>3920</code>. For using the simulation in the iRC desktop software, connect to <code>127.0.0.1</code>, most of the time the port in the simulation is <code>3921</code>, but can be different. Have a look at the log if you are unable to connect. Check whether connection was successfull via the returned bool.</li>
114114
<li>If you want to control the robot, acquire active control via <code>CRIController.set_active_control(True)</code>.</li>
115115
<li>Enable drives with <code>CRIController.enable()</code></li>
116116
<li>Wait unitl axes are ready <code>CRIcontroller.wait_for_kinematics_ready()</code></li>

0 commit comments

Comments
 (0)