Skip to content

Commit 6f347f7

Browse files
committedJul 24, 2024
initial Commit
1 parent bf1b30d commit 6f347f7

12 files changed

+2962
-2
lines changed
 

‎README.md

Lines changed: 37 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,2 +1,37 @@
1-
# CRI-Python-Lib
2-
Library to use Python to interact with the iRC igus Robot Control via the CRI interface
1+
# Introduction
2+
Python package to interface an igus Robot Control via the CRI protocol.
3+
4+
# Current Features
5+
- Robot State
6+
- Basic functions
7+
- Reset
8+
- Enable / Disable
9+
- Acquisition of active control
10+
- Override
11+
- Referencing of
12+
- single axis
13+
- all axes
14+
- Set joints to zero
15+
- Direct movements
16+
- Joint and relative joint
17+
- Cartesian
18+
- Cartesian base and tool relative
19+
- Live jog
20+
- Digital IO and global signals
21+
- Programs
22+
- Upload
23+
- Start / Pause / Stop
24+
- CAN Bridge
25+
26+
# Getting Started
27+
## Installation
28+
Using the library requires no additional libraries, only testing has external dependencies.
29+
30+
In the top directory of this repository execute `pip install .`
31+
32+
## Examples
33+
See `examples` directory.
34+
35+
# Tests
36+
This repository provides pytests for the message parser. They require `pytest` and `pytest-cov`, which can be installed via `pip install -r requirements.txt`. To run the tests (including coverage) execute the following command: `pytest -vv --cov=cri_lib --cov-report term-missing tests`.
37+

‎cri_lib/__init__.py

Lines changed: 25 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,25 @@
1+
"""
2+
.. include:: ../README.md
3+
"""
4+
5+
6+
from .robot_state import (
7+
RobotMode,
8+
KinematicsState,
9+
OperationMode,
10+
RunState,
11+
ReplayMode,
12+
ErrorStates,
13+
RobotCartesianPosition,
14+
PlatformCartesianPosition,
15+
JointsState,
16+
RobotState,
17+
PosVariable,
18+
OperationInfo,
19+
ReferencingAxisState,
20+
ReferencingState,
21+
)
22+
from .cri_controller import CRIController
23+
from .cri_protocol_parser import CRIProtocolParser
24+
25+
from .cri_errors import CRIError, CRIConnectionError, CRICommandTimeOutError

‎cri_lib/cri_controller.py

Lines changed: 1364 additions & 0 deletions
Large diffs are not rendered by default.

‎cri_lib/cri_errors.py

Lines changed: 12 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,12 @@
1+
class CRIError(Exception):
2+
pass
3+
4+
class CRIConnectionError(CRIError):
5+
def __init__(self, message="Not connected to iRC or connection lost."):
6+
self.message = message
7+
super().__init__(self.message)
8+
9+
class CRICommandTimeOutError(CRIError):
10+
def __init__(self, message="Time out waiting for command response."):
11+
self.message = message
12+
super().__init__(self.message)

‎cri_lib/cri_protocol_parser.py

Lines changed: 637 additions & 0 deletions
Large diffs are not rendered by default.

‎cri_lib/robot_state.py

Lines changed: 240 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,240 @@
1+
from dataclasses import dataclass, field
2+
from enum import Enum
3+
4+
5+
class RobotMode(Enum):
6+
JOINT = "joint"
7+
CARTBASE = "cartbase"
8+
CARTTOOL = "carttool"
9+
PLATFORM = "platform"
10+
FSM = "fsm"
11+
12+
13+
class KinematicsState(Enum):
14+
NO_ERROR = 0
15+
JOINT_MIN = 13
16+
JOINT_MAX = 14
17+
SIGULARITY_CENTER = 21
18+
SIGULARITY_REACH = 23
19+
SIGULARITY_WRIST = 24
20+
VIRTUAL_BOX0 = 30
21+
VIRTUAL_BOX1 = 31
22+
VIRTUAL_BOX2 = 32
23+
VIRTUAL_BOX3 = 33
24+
VIRTUAL_BOX4 = 34
25+
VIRTUAL_BOX5 = 35
26+
MOTION_NOT_ALLOWED = 99
27+
28+
29+
class OperationMode(Enum):
30+
NOT_ENABLED = -1
31+
NORMAL = 0
32+
MANUAL = 1
33+
MOTION_NOT_ALLOWED = 2
34+
35+
36+
class RunState(Enum):
37+
STOPPED = 0
38+
PAUSED = 1
39+
RUNNING = 2
40+
41+
42+
class ReplayMode(Enum):
43+
SINGLE = 0
44+
REPEAT = 1
45+
STEP = 2
46+
FAST = 3
47+
48+
49+
@dataclass
50+
class ErrorStates:
51+
over_temp: bool = False
52+
estop_lowv: bool = False
53+
motor_not_enabled: bool = False
54+
com: bool = False
55+
position_lag: bool = False
56+
ENC: bool = False
57+
overcurrent: bool = False
58+
driver: bool = False
59+
60+
61+
@dataclass
62+
class RobotCartesianPosition:
63+
X: float = 0.0
64+
Y: float = 0.0
65+
Z: float = 0.0
66+
A: float = 0.0
67+
B: float = 0.0
68+
C: float = 0.0
69+
70+
71+
@dataclass
72+
class PlatformCartesianPosition:
73+
X: float = 0.0
74+
Y: float = 0.0
75+
RZ: float = 0.0
76+
77+
78+
@dataclass
79+
class JointsState:
80+
A1: float = 0.0
81+
A2: float = 0.0
82+
A3: float = 0.0
83+
A4: float = 0.0
84+
A5: float = 0.0
85+
A6: float = 0.0
86+
E1: float = 0.0
87+
E2: float = 0.0
88+
E3: float = 0.0
89+
G1: float = 0.0
90+
G2: float = 0.0
91+
G3: float = 0.0
92+
P1: float = 0.0
93+
P2: float = 0.0
94+
P3: float = 0.0
95+
P4: float = 0.0
96+
97+
98+
@dataclass
99+
class PosVariable:
100+
X: float = 0.0
101+
Y: float = 0.0
102+
Z: float = 0.0
103+
A: float = 0.0
104+
B: float = 0.0
105+
C: float = 0.0
106+
A1: float = 0.0
107+
A2: float = 0.0
108+
A3: float = 0.0
109+
A4: float = 0.0
110+
A5: float = 0.0
111+
A6: float = 0.0
112+
E1: float = 0.0
113+
E2: float = 0.0
114+
E3: float = 0.0
115+
116+
117+
@dataclass
118+
class OperationInfo:
119+
program_starts_total: int = 0
120+
up_time_complete: float = 0.0
121+
up_time_enabled: float = 0.0
122+
up_time_motion: float = 0.0
123+
up_time_last: float = 0.0
124+
last_programm_duration: int = 0
125+
num_program_starts_since_startup: int = 0
126+
127+
128+
class ReferencingAxisState(Enum):
129+
NOT_REFERENCED = 0
130+
REFERENCED = 1
131+
REFERENCING = 2
132+
133+
@dataclass
134+
class ReferencingState:
135+
global_state:ReferencingAxisState = ReferencingAxisState.NOT_REFERENCED
136+
mandatory: bool = True
137+
ref_prog_enabled: bool = False
138+
ref_prog_running: bool = False
139+
140+
A1: ReferencingAxisState = ReferencingAxisState.NOT_REFERENCED
141+
A2: ReferencingAxisState = ReferencingAxisState.NOT_REFERENCED
142+
A3: ReferencingAxisState = ReferencingAxisState.NOT_REFERENCED
143+
A4: ReferencingAxisState = ReferencingAxisState.NOT_REFERENCED
144+
A5: ReferencingAxisState = ReferencingAxisState.NOT_REFERENCED
145+
A6: ReferencingAxisState = ReferencingAxisState.NOT_REFERENCED
146+
E1: ReferencingAxisState = ReferencingAxisState.NOT_REFERENCED
147+
E2: ReferencingAxisState = ReferencingAxisState.NOT_REFERENCED
148+
E3: ReferencingAxisState = ReferencingAxisState.NOT_REFERENCED
149+
E4: ReferencingAxisState = ReferencingAxisState.NOT_REFERENCED
150+
E5: ReferencingAxisState = ReferencingAxisState.NOT_REFERENCED
151+
E6: ReferencingAxisState = ReferencingAxisState.NOT_REFERENCED
152+
153+
154+
@dataclass
155+
class RobotState:
156+
"""
157+
Dataclass which holds the current state of the robot.
158+
"""
159+
160+
mode: RobotMode = RobotMode.JOINT
161+
joints_set_point: JointsState = field(default_factory=JointsState)
162+
joints_current: JointsState = field(default_factory=JointsState)
163+
164+
position_robot: RobotCartesianPosition = field(
165+
default_factory=RobotCartesianPosition
166+
)
167+
position_platform: PlatformCartesianPosition = field(
168+
default_factory=PlatformCartesianPosition
169+
)
170+
171+
cart_speed_mm_per_s: float = 0.0
172+
173+
override: float = 100.0
174+
175+
din: list[bool] = field(default_factory=lambda: [False] * 64)
176+
dout: list[bool] = field(default_factory=lambda: [False] * 64)
177+
178+
emergency_stop_ok = False
179+
main_relay = False
180+
181+
supply_voltage: float = 0.0
182+
battery_percent: float = 0.0
183+
184+
current_total = 0.0
185+
186+
current_joints: list[float] = field(default_factory=lambda: [0.0] * 16)
187+
188+
kinematics_state: KinematicsState = KinematicsState.MOTION_NOT_ALLOWED
189+
190+
operation_mode: OperationMode = OperationMode.NOT_ENABLED
191+
192+
global_signals: list[bool] = field(default_factory=lambda: [False] * 128)
193+
194+
frame_name: str = ""
195+
frame_position_current: RobotCartesianPosition = field(
196+
default_factory=RobotCartesianPosition
197+
)
198+
199+
main_main_program: str = ""
200+
main_current_program: str = ""
201+
202+
logic_main_program: str = ""
203+
logic_current_program: str = ""
204+
205+
main_commands_count: int = 0
206+
logic_commands_count: int = 0
207+
208+
main_current_command: int = 0
209+
logic_current_command: int = 0
210+
211+
main_runstate: RunState = RunState.STOPPED
212+
logic_runstate: RunState = RunState.STOPPED
213+
214+
main_replay_mode: ReplayMode = ReplayMode.SINGLE
215+
logic_replay_mode: ReplayMode = ReplayMode.SINGLE
216+
217+
error_states: list[ErrorStates] = field(
218+
default_factory=lambda: [ErrorStates()] * 16
219+
)
220+
221+
cycle_time: float = 0.0
222+
workload: float = 0.0
223+
224+
gripper_state: float = 0.0
225+
226+
variabels: dict[str : [PosVariable | float]] = field(default_factory=dict)
227+
228+
operation_info: OperationInfo = field(default_factory=OperationInfo)
229+
230+
active_control: bool = False
231+
232+
robot_control_version: str = ""
233+
234+
robot_configuration: str = ""
235+
robot_type: str = ""
236+
gripper_type: str = ""
237+
238+
project_file: str = ""
239+
240+
referencing_state: ReferencingState = field(default_factory=ReferencingState)

‎examples/relative_move.py

Lines changed: 34 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,34 @@
1+
from cri_lib import CRIController
2+
3+
# CRIController is the main interface for controlling the iRC
4+
controller = CRIController()
5+
6+
#connect to default iRC IP
7+
#controller.connect("192.168.3.11")
8+
if not controller.connect("127.0.0.1", 3921):
9+
print("Unable to connect")
10+
quit()
11+
12+
#acquire active control.
13+
controller.set_active_control(True)
14+
15+
print("enable")
16+
#enable motors
17+
controller.enable()
18+
19+
print("waiting")
20+
#wait until kinematics are ready to move
21+
controller.wait_for_kinematics_ready(10)
22+
23+
controller.set_override(100.0)
24+
25+
print("move")
26+
#relative move x +10mm
27+
controller.move_base_relative(20.0, 20.0, 20.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 10.0, wait_move_finished=True, move_finished_timeout= 1000)
28+
controller.move_base_relative(-20.0, -20.0, -20.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 10.0, wait_move_finished=True, move_finished_timeout= 1000)
29+
30+
31+
32+
#Disable motors and disconnect
33+
controller.disable()
34+
controller.close()

‎examples/start_program.py

Lines changed: 70 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,70 @@
1+
from time import sleep
2+
3+
from cri_lib import CRIController
4+
5+
# CRIController is the main interface for controlling the iRC
6+
controller = CRIController()
7+
8+
#connect to default iRC IP
9+
#if not controller.connect("127.0.0.1", 3921):
10+
if not controller.connect("192.168.3.11"):
11+
print("Unable to connect")
12+
quit()
13+
14+
#acquire active control.
15+
controller.set_active_control(True)
16+
17+
print("enable")
18+
#enable motors
19+
controller.enable()
20+
21+
print("waiting")
22+
#wait until kinematics are ready to move
23+
controller.wait_for_kinematics_ready(10)
24+
25+
controller.set_override(50.0)
26+
27+
print("Load program")
28+
if not controller.load_programm("ReBeL_6DOF_01_Tischtest.xml"):
29+
print("unable to load programm")
30+
controller.disable()
31+
controller.close()
32+
quit()
33+
34+
print("Start program")
35+
if not controller.start_programm():
36+
print("Unable to start programm")
37+
controller.disable()
38+
controller.close()
39+
quit()
40+
41+
sleep(5)
42+
43+
print("Pause program")
44+
if not controller.pause_programm():
45+
print("Unable to pause programm")
46+
controller.disable()
47+
controller.close()
48+
quit()
49+
50+
sleep(5)
51+
52+
print("Start programm again")
53+
if not controller.start_programm():
54+
print("Unable to start programm")
55+
controller.disable()
56+
controller.close()
57+
quit()
58+
59+
sleep(5)
60+
61+
print("Stop program")
62+
if not controller.stop_programm():
63+
print("Unable to stop programm")
64+
controller.disable()
65+
controller.close()
66+
quit()
67+
68+
#Disable motors and disconnect
69+
controller.disable()
70+
controller.close()

‎pyproject.toml

Lines changed: 13 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,13 @@
1+
[project]
2+
name = "cri_lib"
3+
dynamic = ["version"]
4+
description = "Client library for accessing igus Robot Control via CRI network interface."
5+
readme = "README.md"
6+
requires-python = ">=3.10"
7+
authors = [
8+
{ name = "Bastian Richter", email = "brichter@igus.net" },
9+
]
10+
dependencies = []
11+
12+
[tool.setuptools]
13+
packages = ["cri_lib"]

‎requirements.txt

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,2 @@
1+
pytest
2+
pytest-cov

‎tests/__init__.py

Whitespace-only changes.

‎tests/test_cri_parser.py

Lines changed: 528 additions & 0 deletions
Large diffs are not rendered by default.

0 commit comments

Comments
 (0)
Please sign in to comment.