ABBRobotEGM 1.0.1__tar.gz

Sign up to get free protection for your applications and to get access to all the features.
@@ -0,0 +1,201 @@
1
+ Apache License
2
+ Version 2.0, January 2004
3
+ http://www.apache.org/licenses/
4
+
5
+ TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION
6
+
7
+ 1. Definitions.
8
+
9
+ "License" shall mean the terms and conditions for use, reproduction,
10
+ and distribution as defined by Sections 1 through 9 of this document.
11
+
12
+ "Licensor" shall mean the copyright owner or entity authorized by
13
+ the copyright owner that is granting the License.
14
+
15
+ "Legal Entity" shall mean the union of the acting entity and all
16
+ other entities that control, are controlled by, or are under common
17
+ control with that entity. For the purposes of this definition,
18
+ "control" means (i) the power, direct or indirect, to cause the
19
+ direction or management of such entity, whether by contract or
20
+ otherwise, or (ii) ownership of fifty percent (50%) or more of the
21
+ outstanding shares, or (iii) beneficial ownership of such entity.
22
+
23
+ "You" (or "Your") shall mean an individual or Legal Entity
24
+ exercising permissions granted by this License.
25
+
26
+ "Source" form shall mean the preferred form for making modifications,
27
+ including but not limited to software source code, documentation
28
+ source, and configuration files.
29
+
30
+ "Object" form shall mean any form resulting from mechanical
31
+ transformation or translation of a Source form, including but
32
+ not limited to compiled object code, generated documentation,
33
+ and conversions to other media types.
34
+
35
+ "Work" shall mean the work of authorship, whether in Source or
36
+ Object form, made available under the License, as indicated by a
37
+ copyright notice that is included in or attached to the work
38
+ (an example is provided in the Appendix below).
39
+
40
+ "Derivative Works" shall mean any work, whether in Source or Object
41
+ form, that is based on (or derived from) the Work and for which the
42
+ editorial revisions, annotations, elaborations, or other modifications
43
+ represent, as a whole, an original work of authorship. For the purposes
44
+ of this License, Derivative Works shall not include works that remain
45
+ separable from, or merely link (or bind by name) to the interfaces of,
46
+ the Work and Derivative Works thereof.
47
+
48
+ "Contribution" shall mean any work of authorship, including
49
+ the original version of the Work and any modifications or additions
50
+ to that Work or Derivative Works thereof, that is intentionally
51
+ submitted to Licensor for inclusion in the Work by the copyright owner
52
+ or by an individual or Legal Entity authorized to submit on behalf of
53
+ the copyright owner. For the purposes of this definition, "submitted"
54
+ means any form of electronic, verbal, or written communication sent
55
+ to the Licensor or its representatives, including but not limited to
56
+ communication on electronic mailing lists, source code control systems,
57
+ and issue tracking systems that are managed by, or on behalf of, the
58
+ Licensor for the purpose of discussing and improving the Work, but
59
+ excluding communication that is conspicuously marked or otherwise
60
+ designated in writing by the copyright owner as "Not a Contribution."
61
+
62
+ "Contributor" shall mean Licensor and any individual or Legal Entity
63
+ on behalf of whom a Contribution has been received by Licensor and
64
+ subsequently incorporated within the Work.
65
+
66
+ 2. Grant of Copyright License. Subject to the terms and conditions of
67
+ this License, each Contributor hereby grants to You a perpetual,
68
+ worldwide, non-exclusive, no-charge, royalty-free, irrevocable
69
+ copyright license to reproduce, prepare Derivative Works of,
70
+ publicly display, publicly perform, sublicense, and distribute the
71
+ Work and such Derivative Works in Source or Object form.
72
+
73
+ 3. Grant of Patent License. Subject to the terms and conditions of
74
+ this License, each Contributor hereby grants to You a perpetual,
75
+ worldwide, non-exclusive, no-charge, royalty-free, irrevocable
76
+ (except as stated in this section) patent license to make, have made,
77
+ use, offer to sell, sell, import, and otherwise transfer the Work,
78
+ where such license applies only to those patent claims licensable
79
+ by such Contributor that are necessarily infringed by their
80
+ Contribution(s) alone or by combination of their Contribution(s)
81
+ with the Work to which such Contribution(s) was submitted. If You
82
+ institute patent litigation against any entity (including a
83
+ cross-claim or counterclaim in a lawsuit) alleging that the Work
84
+ or a Contribution incorporated within the Work constitutes direct
85
+ or contributory patent infringement, then any patent licenses
86
+ granted to You under this License for that Work shall terminate
87
+ as of the date such litigation is filed.
88
+
89
+ 4. Redistribution. You may reproduce and distribute copies of the
90
+ Work or Derivative Works thereof in any medium, with or without
91
+ modifications, and in Source or Object form, provided that You
92
+ meet the following conditions:
93
+
94
+ (a) You must give any other recipients of the Work or
95
+ Derivative Works a copy of this License; and
96
+
97
+ (b) You must cause any modified files to carry prominent notices
98
+ stating that You changed the files; and
99
+
100
+ (c) You must retain, in the Source form of any Derivative Works
101
+ that You distribute, all copyright, patent, trademark, and
102
+ attribution notices from the Source form of the Work,
103
+ excluding those notices that do not pertain to any part of
104
+ the Derivative Works; and
105
+
106
+ (d) If the Work includes a "NOTICE" text file as part of its
107
+ distribution, then any Derivative Works that You distribute must
108
+ include a readable copy of the attribution notices contained
109
+ within such NOTICE file, excluding those notices that do not
110
+ pertain to any part of the Derivative Works, in at least one
111
+ of the following places: within a NOTICE text file distributed
112
+ as part of the Derivative Works; within the Source form or
113
+ documentation, if provided along with the Derivative Works; or,
114
+ within a display generated by the Derivative Works, if and
115
+ wherever such third-party notices normally appear. The contents
116
+ of the NOTICE file are for informational purposes only and
117
+ do not modify the License. You may add Your own attribution
118
+ notices within Derivative Works that You distribute, alongside
119
+ or as an addendum to the NOTICE text from the Work, provided
120
+ that such additional attribution notices cannot be construed
121
+ as modifying the License.
122
+
123
+ You may add Your own copyright statement to Your modifications and
124
+ may provide additional or different license terms and conditions
125
+ for use, reproduction, or distribution of Your modifications, or
126
+ for any such Derivative Works as a whole, provided Your use,
127
+ reproduction, and distribution of the Work otherwise complies with
128
+ the conditions stated in this License.
129
+
130
+ 5. Submission of Contributions. Unless You explicitly state otherwise,
131
+ any Contribution intentionally submitted for inclusion in the Work
132
+ by You to the Licensor shall be under the terms and conditions of
133
+ this License, without any additional terms or conditions.
134
+ Notwithstanding the above, nothing herein shall supersede or modify
135
+ the terms of any separate license agreement you may have executed
136
+ with Licensor regarding such Contributions.
137
+
138
+ 6. Trademarks. This License does not grant permission to use the trade
139
+ names, trademarks, service marks, or product names of the Licensor,
140
+ except as required for reasonable and customary use in describing the
141
+ origin of the Work and reproducing the content of the NOTICE file.
142
+
143
+ 7. Disclaimer of Warranty. Unless required by applicable law or
144
+ agreed to in writing, Licensor provides the Work (and each
145
+ Contributor provides its Contributions) on an "AS IS" BASIS,
146
+ WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or
147
+ implied, including, without limitation, any warranties or conditions
148
+ of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A
149
+ PARTICULAR PURPOSE. You are solely responsible for determining the
150
+ appropriateness of using or redistributing the Work and assume any
151
+ risks associated with Your exercise of permissions under this License.
152
+
153
+ 8. Limitation of Liability. In no event and under no legal theory,
154
+ whether in tort (including negligence), contract, or otherwise,
155
+ unless required by applicable law (such as deliberate and grossly
156
+ negligent acts) or agreed to in writing, shall any Contributor be
157
+ liable to You for damages, including any direct, indirect, special,
158
+ incidental, or consequential damages of any character arising as a
159
+ result of this License or out of the use or inability to use the
160
+ Work (including but not limited to damages for loss of goodwill,
161
+ work stoppage, computer failure or malfunction, or any and all
162
+ other commercial damages or losses), even if such Contributor
163
+ has been advised of the possibility of such damages.
164
+
165
+ 9. Accepting Warranty or Additional Liability. While redistributing
166
+ the Work or Derivative Works thereof, You may choose to offer,
167
+ and charge a fee for, acceptance of support, warranty, indemnity,
168
+ or other liability obligations and/or rights consistent with this
169
+ License. However, in accepting such obligations, You may act only
170
+ on Your own behalf and on Your sole responsibility, not on behalf
171
+ of any other Contributor, and only if You agree to indemnify,
172
+ defend, and hold each Contributor harmless for any liability
173
+ incurred by, or claims asserted against, such Contributor by reason
174
+ of your accepting any such warranty or additional liability.
175
+
176
+ END OF TERMS AND CONDITIONS
177
+
178
+ APPENDIX: How to apply the Apache License to your work.
179
+
180
+ To apply the Apache License to your work, attach the following
181
+ boilerplate notice, with the fields enclosed by brackets "[]"
182
+ replaced with your own identifying information. (Don't include
183
+ the brackets!) The text should be enclosed in the appropriate
184
+ comment syntax for the file format. We also recommend that a
185
+ file or class name and description of purpose be included on the
186
+ same "printed page" as the copyright notice for easier
187
+ identification within third-party archives.
188
+
189
+ Copyright [yyyy] [name of copyright owner]
190
+
191
+ Licensed under the Apache License, Version 2.0 (the "License");
192
+ you may not use this file except in compliance with the License.
193
+ You may obtain a copy of the License at
194
+
195
+ http://www.apache.org/licenses/LICENSE-2.0
196
+
197
+ Unless required by applicable law or agreed to in writing, software
198
+ distributed under the License is distributed on an "AS IS" BASIS,
199
+ WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
200
+ See the License for the specific language governing permissions and
201
+ limitations under the License.
@@ -0,0 +1,2 @@
1
+ include LICENSE
2
+ include README.md
@@ -0,0 +1,138 @@
1
+ Metadata-Version: 2.2
2
+ Name: ABBRobotEGM
3
+ Version: 1.0.1
4
+ Summary: A Python library for real-time control and data streaming of ABB robots using EGM protocol, enabling high-frequency (250Hz) communication through UDP for industrial automation applications.
5
+ Home-page: https://github.com/FLo-ABB/ABB-EGM-Python
6
+ Author: Florian LOBERT
7
+ Classifier: Programming Language :: Python :: 3
8
+ Classifier: License :: OSI Approved :: Apache Software License
9
+ Classifier: Operating System :: OS Independent
10
+ Classifier: Intended Audience :: Developers
11
+ Requires-Python: >=3.6
12
+ Description-Content-Type: text/markdown
13
+ License-File: LICENSE
14
+ Requires-Dist: numpy
15
+ Requires-Dist: protobuf
16
+ Dynamic: author
17
+ Dynamic: classifier
18
+ Dynamic: description
19
+ Dynamic: description-content-type
20
+ Dynamic: home-page
21
+ Dynamic: requires-dist
22
+ Dynamic: requires-python
23
+ Dynamic: summary
24
+
25
+ # ABBRobotEGM
26
+
27
+ ![License](https://img.shields.io/badge/License-Apache%202.0-blue.svg)
28
+
29
+ `ABBRobotEGM` is a Python library for interfacing with ABB robots using Externally Guided Motion (EGM). This library provides real-time streaming communication with ABB robots at rates up to 250Hz using UDP. It's based on the official ABB EGM [documentation](https://github.com/FLo-ABB/ABB-EGM-Python/blob/main/doc/3HAC073318%20AM%20Externally%20Guided%20Motion%20RW7-en.pdf) and examples, and it's designed to be easy to use and to integrate with other systems.
30
+
31
+ ## Prerequisites
32
+
33
+ - Python 3.x
34
+ - ABB RobotWare 7.X (should work with 6.X with few modifications)
35
+ - ABB Robot with EGM option (3124-1 Externally Guided Motion)
36
+
37
+
38
+ ## Installation 🚀
39
+
40
+ ### Using pip 🐍
41
+
42
+ To install the library using pip, run the following command:
43
+
44
+ ```bash
45
+ pip install ABBRobotEGM
46
+ ```
47
+
48
+ ### Manual Installation 📦
49
+
50
+ To use this library in your project, first download the repository and place the `ABBRobotEGM` folder in your project's directory. You can then import the `EGM` class from this library to use it in your project.
51
+
52
+ ## Simple Examples
53
+
54
+ The repository includes several examples demonstrating different EGM functionalities. Inside each python example file, you can find the relative **RAPID** code that should be running on the robot controller.
55
+
56
+ ### Guidance Mode
57
+
58
+ #### 1. Joint
59
+
60
+ example_joint_guidance.py - Makes the first joint oscillate between -45° and +45°:
61
+
62
+ #### 2. Cartesian
63
+ example_pose_guidance.py - Makes the robot move in a circular pattern
64
+
65
+ ### Streaming Mode
66
+
67
+ #### 1. Joint Streaming
68
+ example_joint_stream.py - Streams robot joint positions :
69
+ ```python
70
+ from ABBRobotEGM import EGM
71
+
72
+ def main() -> None:
73
+ """
74
+ Example showing how to stream the robot's position.
75
+ Be sure the robot is running before running this script.
76
+ """
77
+ with EGM() as egm:
78
+ while True:
79
+ success, state = egm.receive_from_robot()
80
+ if not success:
81
+ print("Failed to receive from robot")
82
+ break
83
+ print(f"{state.clock[1]}, {state.joint_angles[0]}, {state.joint_angles[1]}, {state.joint_angles[2]}, {state.joint_angles[3]}, {state.joint_angles[4]}, {state.joint_angles[5]}")
84
+
85
+
86
+ if __name__ == "__main__":
87
+ main()
88
+
89
+ ```
90
+
91
+
92
+ #### 2. Cartesian Streaming
93
+ example_pos_stream.py - Streams robot cartesian position
94
+ ```python
95
+ from ABBRobotEGM import EGM
96
+
97
+ def main() -> None:
98
+ """
99
+ Example showing how to stream the robot's position.
100
+ Be sure the robot is running before running this script.
101
+ """
102
+ with EGM() as egm:
103
+ while True:
104
+ success, state = egm.receive_from_robot()
105
+ if not success:
106
+ print("Failed to receive from robot")
107
+ break
108
+ print(f"{state.clock[1]}, {state.cartesian.pos.x}, {state.cartesian.pos.y}, {state.cartesian.pos.z}")
109
+
110
+
111
+ if __name__ == "__main__":
112
+ main()
113
+ ```
114
+
115
+ ### 3. Data Exchange
116
+ example_table.py - Demonstrates exchanging data arrays with the robot
117
+
118
+ ## Complex Scenario
119
+ Example of a more complex scenario where the robot is scanning a surface giving in real time its tool center point position and correlating with a sensor reading. Rspag and python code available in *"scenario scan"* folder.
120
+
121
+ https://github.com/user-attachments/assets/03f151de-e098-4255-ac46-7dff42231071
122
+
123
+ ## Features 🚀
124
+
125
+ - Real-time communication at up to 250Hz
126
+ - Joint position control
127
+ - Cartesian position control
128
+ - Position streaming
129
+ - Path corrections
130
+ - RAPID data exchange
131
+ - External axis support
132
+ - Force measurement reading
133
+ - Comprehensive robot state feedback
134
+
135
+
136
+ ## Contributing 🤝
137
+
138
+ Contributions are welcome! Please feel free to submit pull requests.
@@ -0,0 +1,114 @@
1
+ # ABBRobotEGM
2
+
3
+ ![License](https://img.shields.io/badge/License-Apache%202.0-blue.svg)
4
+
5
+ `ABBRobotEGM` is a Python library for interfacing with ABB robots using Externally Guided Motion (EGM). This library provides real-time streaming communication with ABB robots at rates up to 250Hz using UDP. It's based on the official ABB EGM [documentation](https://github.com/FLo-ABB/ABB-EGM-Python/blob/main/doc/3HAC073318%20AM%20Externally%20Guided%20Motion%20RW7-en.pdf) and examples, and it's designed to be easy to use and to integrate with other systems.
6
+
7
+ ## Prerequisites
8
+
9
+ - Python 3.x
10
+ - ABB RobotWare 7.X (should work with 6.X with few modifications)
11
+ - ABB Robot with EGM option (3124-1 Externally Guided Motion)
12
+
13
+
14
+ ## Installation 🚀
15
+
16
+ ### Using pip 🐍
17
+
18
+ To install the library using pip, run the following command:
19
+
20
+ ```bash
21
+ pip install ABBRobotEGM
22
+ ```
23
+
24
+ ### Manual Installation 📦
25
+
26
+ To use this library in your project, first download the repository and place the `ABBRobotEGM` folder in your project's directory. You can then import the `EGM` class from this library to use it in your project.
27
+
28
+ ## Simple Examples
29
+
30
+ The repository includes several examples demonstrating different EGM functionalities. Inside each python example file, you can find the relative **RAPID** code that should be running on the robot controller.
31
+
32
+ ### Guidance Mode
33
+
34
+ #### 1. Joint
35
+
36
+ example_joint_guidance.py - Makes the first joint oscillate between -45° and +45°:
37
+
38
+ #### 2. Cartesian
39
+ example_pose_guidance.py - Makes the robot move in a circular pattern
40
+
41
+ ### Streaming Mode
42
+
43
+ #### 1. Joint Streaming
44
+ example_joint_stream.py - Streams robot joint positions :
45
+ ```python
46
+ from ABBRobotEGM import EGM
47
+
48
+ def main() -> None:
49
+ """
50
+ Example showing how to stream the robot's position.
51
+ Be sure the robot is running before running this script.
52
+ """
53
+ with EGM() as egm:
54
+ while True:
55
+ success, state = egm.receive_from_robot()
56
+ if not success:
57
+ print("Failed to receive from robot")
58
+ break
59
+ print(f"{state.clock[1]}, {state.joint_angles[0]}, {state.joint_angles[1]}, {state.joint_angles[2]}, {state.joint_angles[3]}, {state.joint_angles[4]}, {state.joint_angles[5]}")
60
+
61
+
62
+ if __name__ == "__main__":
63
+ main()
64
+
65
+ ```
66
+
67
+
68
+ #### 2. Cartesian Streaming
69
+ example_pos_stream.py - Streams robot cartesian position
70
+ ```python
71
+ from ABBRobotEGM import EGM
72
+
73
+ def main() -> None:
74
+ """
75
+ Example showing how to stream the robot's position.
76
+ Be sure the robot is running before running this script.
77
+ """
78
+ with EGM() as egm:
79
+ while True:
80
+ success, state = egm.receive_from_robot()
81
+ if not success:
82
+ print("Failed to receive from robot")
83
+ break
84
+ print(f"{state.clock[1]}, {state.cartesian.pos.x}, {state.cartesian.pos.y}, {state.cartesian.pos.z}")
85
+
86
+
87
+ if __name__ == "__main__":
88
+ main()
89
+ ```
90
+
91
+ ### 3. Data Exchange
92
+ example_table.py - Demonstrates exchanging data arrays with the robot
93
+
94
+ ## Complex Scenario
95
+ Example of a more complex scenario where the robot is scanning a surface giving in real time its tool center point position and correlating with a sensor reading. Rspag and python code available in *"scenario scan"* folder.
96
+
97
+ https://github.com/user-attachments/assets/03f151de-e098-4255-ac46-7dff42231071
98
+
99
+ ## Features 🚀
100
+
101
+ - Real-time communication at up to 250Hz
102
+ - Joint position control
103
+ - Cartesian position control
104
+ - Position streaming
105
+ - Path corrections
106
+ - RAPID data exchange
107
+ - External axis support
108
+ - Force measurement reading
109
+ - Comprehensive robot state feedback
110
+
111
+
112
+ ## Contributing 🤝
113
+
114
+ Contributions are welcome! Please feel free to submit pull requests.
@@ -0,0 +1,4 @@
1
+ [egg_info]
2
+ tag_build =
3
+ tag_date = 0
4
+
@@ -0,0 +1,24 @@
1
+ from setuptools import setup, find_packages
2
+
3
+ setup(
4
+ name='ABBRobotEGM',
5
+ version='v1.0.1',
6
+ description='A Python library for real-time control and data streaming of ABB robots using EGM protocol, enabling high-frequency (250Hz) communication through UDP for industrial automation applications.',
7
+ long_description=open('README.md', encoding='utf-8').read(),
8
+ long_description_content_type='text/markdown',
9
+ author='Florian LOBERT',
10
+ url='https://github.com/FLo-ABB/ABB-EGM-Python',
11
+ packages=find_packages(where='src'),
12
+ package_dir={'': 'src'},
13
+ classifiers=[
14
+ 'Programming Language :: Python :: 3',
15
+ 'License :: OSI Approved :: Apache Software License', # Fixed classifier
16
+ 'Operating System :: OS Independent',
17
+ 'Intended Audience :: Developers',
18
+ ],
19
+ python_requires='>=3.6', # Specify minimum Python version
20
+ install_requires=[
21
+ 'numpy',
22
+ 'protobuf',
23
+ ],
24
+ )
@@ -0,0 +1 @@
1
+ from .egm import EGM
@@ -0,0 +1,78 @@
1
+ # -*- coding: utf-8 -*-
2
+ # Generated by the protocol buffer compiler. DO NOT EDIT!
3
+ # source: egm.proto
4
+ # Protobuf Python Version: 4.25.6
5
+ """Generated protocol buffer code."""
6
+ from google.protobuf import descriptor as _descriptor
7
+ from google.protobuf import descriptor_pool as _descriptor_pool
8
+ from google.protobuf import symbol_database as _symbol_database
9
+ from google.protobuf.internal import builder as _builder
10
+ # @@protoc_insertion_point(imports)
11
+
12
+ _sym_db = _symbol_database.Default()
13
+
14
+
15
+ DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile(b'\n\tegm.proto\x12\x07\x61\x62\x62.egm\"\xeb\x01\n\tEgmHeader\x12\r\n\x05seqno\x18\x01 \x01(\r\x12\n\n\x02tm\x18\x02 \x01(\r\x12@\n\x05mtype\x18\x03 \x01(\x0e\x32\x1e.abb.egm.EgmHeader.MessageType:\x11MSGTYPE_UNDEFINED\"\x80\x01\n\x0bMessageType\x12\x15\n\x11MSGTYPE_UNDEFINED\x10\x00\x12\x13\n\x0fMSGTYPE_COMMAND\x10\x01\x12\x10\n\x0cMSGTYPE_DATA\x10\x02\x12\x16\n\x12MSGTYPE_CORRECTION\x10\x03\x12\x1b\n\x17MSGTYPE_PATH_CORRECTION\x10\x04\"/\n\x0c\x45gmCartesian\x12\t\n\x01x\x18\x01 \x02(\x01\x12\t\n\x01y\x18\x02 \x02(\x01\x12\t\n\x01z\x18\x03 \x02(\x01\"?\n\rEgmQuaternion\x12\n\n\x02u0\x18\x01 \x02(\x01\x12\n\n\x02u1\x18\x02 \x02(\x01\x12\n\n\x02u2\x18\x03 \x02(\x01\x12\n\n\x02u3\x18\x04 \x02(\x01\"+\n\x08\x45gmEuler\x12\t\n\x01x\x18\x01 \x02(\x01\x12\t\n\x01y\x18\x02 \x02(\x01\x12\t\n\x01z\x18\x03 \x02(\x01\"%\n\x08\x45gmClock\x12\x0b\n\x03sec\x18\x01 \x02(\x04\x12\x0c\n\x04usec\x18\x02 \x02(\x04\")\n\x0c\x45gmTimestamp\x12\x0b\n\x03sec\x18\x01 \x01(\x04\x12\x0c\n\x04nsec\x18\x02 \x01(\x04\"w\n\x07\x45gmPose\x12\"\n\x03pos\x18\x01 \x01(\x0b\x32\x15.abb.egm.EgmCartesian\x12&\n\x06orient\x18\x02 \x01(\x0b\x32\x16.abb.egm.EgmQuaternion\x12 \n\x05\x65uler\x18\x03 \x01(\x0b\x32\x11.abb.egm.EgmEuler\"\"\n\x11\x45gmCartesianSpeed\x12\r\n\x05value\x18\x01 \x03(\x01\"\x1b\n\tEgmJoints\x12\x0e\n\x06joints\x18\x01 \x03(\x01\"#\n\x11\x45gmExternalJoints\x12\x0e\n\x06joints\x18\x01 \x03(\x01\"\xcc\x01\n\nEgmPlanned\x12\"\n\x06joints\x18\x01 \x01(\x0b\x32\x12.abb.egm.EgmJoints\x12#\n\tcartesian\x18\x02 \x01(\x0b\x32\x10.abb.egm.EgmPose\x12*\n\x0e\x65xternalJoints\x18\x03 \x01(\x0b\x32\x12.abb.egm.EgmJoints\x12\x1f\n\x04time\x18\x04 \x01(\x0b\x32\x11.abb.egm.EgmClock\x12(\n\ttimeStamp\x18\x05 \x01(\x0b\x32\x15.abb.egm.EgmTimestamp\"\x8d\x01\n\x0b\x45gmSpeedRef\x12\"\n\x06joints\x18\x01 \x01(\x0b\x32\x12.abb.egm.EgmJoints\x12.\n\ncartesians\x18\x02 \x01(\x0b\x32\x1a.abb.egm.EgmCartesianSpeed\x12*\n\x0e\x65xternalJoints\x18\x03 \x01(\x0b\x32\x12.abb.egm.EgmJoints\">\n\x0b\x45gmPathCorr\x12\"\n\x03pos\x18\x01 \x02(\x0b\x32\x15.abb.egm.EgmCartesian\x12\x0b\n\x03\x61ge\x18\x02 \x02(\r\"\xcd\x01\n\x0b\x45gmFeedBack\x12\"\n\x06joints\x18\x01 \x01(\x0b\x32\x12.abb.egm.EgmJoints\x12#\n\tcartesian\x18\x02 \x01(\x0b\x32\x10.abb.egm.EgmPose\x12*\n\x0e\x65xternalJoints\x18\x03 \x01(\x0b\x32\x12.abb.egm.EgmJoints\x12\x1f\n\x04time\x18\x04 \x01(\x0b\x32\x11.abb.egm.EgmClock\x12(\n\ttimeStamp\x18\x05 \x01(\x0b\x32\x15.abb.egm.EgmTimestamp\"\x8c\x01\n\rEgmMotorState\x12\x34\n\x05state\x18\x01 \x02(\x0e\x32%.abb.egm.EgmMotorState.MotorStateType\"E\n\x0eMotorStateType\x12\x14\n\x10MOTORS_UNDEFINED\x10\x00\x12\r\n\tMOTORS_ON\x10\x01\x12\x0e\n\nMOTORS_OFF\x10\x02\"\xa2\x01\n\x0b\x45gmMCIState\x12?\n\x05state\x18\x01 \x02(\x0e\x32!.abb.egm.EgmMCIState.MCIStateType:\rMCI_UNDEFINED\"R\n\x0cMCIStateType\x12\x11\n\rMCI_UNDEFINED\x10\x00\x12\r\n\tMCI_ERROR\x10\x01\x12\x0f\n\x0bMCI_STOPPED\x10\x02\x12\x0f\n\x0bMCI_RUNNING\x10\x03\"\xc3\x01\n\x15\x45gmRapidCtrlExecState\x12U\n\x05state\x18\x01 \x02(\x0e\x32\x35.abb.egm.EgmRapidCtrlExecState.RapidCtrlExecStateType:\x0fRAPID_UNDEFINED\"S\n\x16RapidCtrlExecStateType\x12\x13\n\x0fRAPID_UNDEFINED\x10\x00\x12\x11\n\rRAPID_STOPPED\x10\x01\x12\x11\n\rRAPID_RUNNING\x10\x02\"!\n\x0e\x45gmTestSignals\x12\x0f\n\x07signals\x18\x01 \x03(\x01\"3\n\x10\x45gmMeasuredForce\x12\x10\n\x08\x66\x63\x41\x63tive\x18\x01 \x01(\x08\x12\r\n\x05\x66orce\x18\x02 \x03(\x01\"C\n\x10\x45gmCollisionInfo\x12\x19\n\x11\x63ollsionTriggered\x18\x01 \x01(\x08\x12\x14\n\x0c\x63ollDetQuota\x18\x02 \x03(\x01\",\n\x0c\x45gmRAPIDdata\x12\x0e\n\x06\x64igVal\x18\x01 \x01(\x08\x12\x0c\n\x04\x64num\x18\x02 \x03(\x01\"\xb7\x04\n\x08\x45gmRobot\x12\"\n\x06header\x18\x01 \x01(\x0b\x32\x12.abb.egm.EgmHeader\x12&\n\x08\x66\x65\x65\x64\x42\x61\x63k\x18\x02 \x01(\x0b\x32\x14.abb.egm.EgmFeedBack\x12$\n\x07planned\x18\x03 \x01(\x0b\x32\x13.abb.egm.EgmPlanned\x12*\n\nmotorState\x18\x04 \x01(\x0b\x32\x16.abb.egm.EgmMotorState\x12&\n\x08mciState\x18\x05 \x01(\x0b\x32\x14.abb.egm.EgmMCIState\x12\x19\n\x11mciConvergenceMet\x18\x06 \x01(\x08\x12,\n\x0btestSignals\x18\x07 \x01(\x0b\x32\x17.abb.egm.EgmTestSignals\x12\x36\n\x0erapidExecState\x18\x08 \x01(\x0b\x32\x1e.abb.egm.EgmRapidCtrlExecState\x12\x30\n\rmeasuredForce\x18\t \x01(\x0b\x32\x19.abb.egm.EgmMeasuredForce\x12\x17\n\x0futilizationRate\x18\n \x01(\x01\x12\x11\n\tmoveIndex\x18\x0b \x01(\r\x12\x30\n\rCollisionInfo\x18\x0c \x01(\x0b\x32\x19.abb.egm.EgmCollisionInfo\x12-\n\x0eRAPIDfromRobot\x18\r \x01(\x0b\x32\x15.abb.egm.EgmRAPIDdata\x12%\n\ttorqueRef\x18\x0e \x01(\x0b\x32\x12.abb.egm.EgmJoints\"\xaa\x01\n\tEgmSensor\x12\"\n\x06header\x18\x01 \x01(\x0b\x32\x12.abb.egm.EgmHeader\x12$\n\x07planned\x18\x02 \x01(\x0b\x32\x13.abb.egm.EgmPlanned\x12&\n\x08speedRef\x18\x03 \x01(\x0b\x32\x14.abb.egm.EgmSpeedRef\x12+\n\x0cRAPIDtoRobot\x18\x04 \x01(\x0b\x32\x15.abb.egm.EgmRAPIDdata\"_\n\x11\x45gmSensorPathCorr\x12\"\n\x06header\x18\x01 \x01(\x0b\x32\x12.abb.egm.EgmHeader\x12&\n\x08pathCorr\x18\x02 \x01(\x0b\x32\x14.abb.egm.EgmPathCorr')
16
+
17
+ _globals = globals()
18
+ _builder.BuildMessageAndEnumDescriptors(DESCRIPTOR, _globals)
19
+ _builder.BuildTopDescriptorsAndMessages(DESCRIPTOR, 'egm_pb2', _globals)
20
+ if _descriptor._USE_C_DESCRIPTORS is False:
21
+ DESCRIPTOR._options = None
22
+ _globals['_EGMHEADER']._serialized_start = 23
23
+ _globals['_EGMHEADER']._serialized_end = 258
24
+ _globals['_EGMHEADER_MESSAGETYPE']._serialized_start = 130
25
+ _globals['_EGMHEADER_MESSAGETYPE']._serialized_end = 258
26
+ _globals['_EGMCARTESIAN']._serialized_start = 260
27
+ _globals['_EGMCARTESIAN']._serialized_end = 307
28
+ _globals['_EGMQUATERNION']._serialized_start = 309
29
+ _globals['_EGMQUATERNION']._serialized_end = 372
30
+ _globals['_EGMEULER']._serialized_start = 374
31
+ _globals['_EGMEULER']._serialized_end = 417
32
+ _globals['_EGMCLOCK']._serialized_start = 419
33
+ _globals['_EGMCLOCK']._serialized_end = 456
34
+ _globals['_EGMTIMESTAMP']._serialized_start = 458
35
+ _globals['_EGMTIMESTAMP']._serialized_end = 499
36
+ _globals['_EGMPOSE']._serialized_start = 501
37
+ _globals['_EGMPOSE']._serialized_end = 620
38
+ _globals['_EGMCARTESIANSPEED']._serialized_start = 622
39
+ _globals['_EGMCARTESIANSPEED']._serialized_end = 656
40
+ _globals['_EGMJOINTS']._serialized_start = 658
41
+ _globals['_EGMJOINTS']._serialized_end = 685
42
+ _globals['_EGMEXTERNALJOINTS']._serialized_start = 687
43
+ _globals['_EGMEXTERNALJOINTS']._serialized_end = 722
44
+ _globals['_EGMPLANNED']._serialized_start = 725
45
+ _globals['_EGMPLANNED']._serialized_end = 929
46
+ _globals['_EGMSPEEDREF']._serialized_start = 932
47
+ _globals['_EGMSPEEDREF']._serialized_end = 1073
48
+ _globals['_EGMPATHCORR']._serialized_start = 1075
49
+ _globals['_EGMPATHCORR']._serialized_end = 1137
50
+ _globals['_EGMFEEDBACK']._serialized_start = 1140
51
+ _globals['_EGMFEEDBACK']._serialized_end = 1345
52
+ _globals['_EGMMOTORSTATE']._serialized_start = 1348
53
+ _globals['_EGMMOTORSTATE']._serialized_end = 1488
54
+ _globals['_EGMMOTORSTATE_MOTORSTATETYPE']._serialized_start = 1419
55
+ _globals['_EGMMOTORSTATE_MOTORSTATETYPE']._serialized_end = 1488
56
+ _globals['_EGMMCISTATE']._serialized_start = 1491
57
+ _globals['_EGMMCISTATE']._serialized_end = 1653
58
+ _globals['_EGMMCISTATE_MCISTATETYPE']._serialized_start = 1571
59
+ _globals['_EGMMCISTATE_MCISTATETYPE']._serialized_end = 1653
60
+ _globals['_EGMRAPIDCTRLEXECSTATE']._serialized_start = 1656
61
+ _globals['_EGMRAPIDCTRLEXECSTATE']._serialized_end = 1851
62
+ _globals['_EGMRAPIDCTRLEXECSTATE_RAPIDCTRLEXECSTATETYPE']._serialized_start = 1768
63
+ _globals['_EGMRAPIDCTRLEXECSTATE_RAPIDCTRLEXECSTATETYPE']._serialized_end = 1851
64
+ _globals['_EGMTESTSIGNALS']._serialized_start = 1853
65
+ _globals['_EGMTESTSIGNALS']._serialized_end = 1886
66
+ _globals['_EGMMEASUREDFORCE']._serialized_start = 1888
67
+ _globals['_EGMMEASUREDFORCE']._serialized_end = 1939
68
+ _globals['_EGMCOLLISIONINFO']._serialized_start = 1941
69
+ _globals['_EGMCOLLISIONINFO']._serialized_end = 2008
70
+ _globals['_EGMRAPIDDATA']._serialized_start = 2010
71
+ _globals['_EGMRAPIDDATA']._serialized_end = 2054
72
+ _globals['_EGMROBOT']._serialized_start = 2057
73
+ _globals['_EGMROBOT']._serialized_end = 2624
74
+ _globals['_EGMSENSOR']._serialized_start = 2627
75
+ _globals['_EGMSENSOR']._serialized_end = 2797
76
+ _globals['_EGMSENSORPATHCORR']._serialized_start = 2799
77
+ _globals['_EGMSENSORPATHCORR']._serialized_end = 2894
78
+ # @@protoc_insertion_point(module_scope)
@@ -0,0 +1,64 @@
1
+ from typing import NamedTuple
2
+
3
+
4
+ class Orientation(NamedTuple):
5
+ """
6
+ A class used to represent an Orientation in 3D space using quaternions.
7
+
8
+ Attributes
9
+ ----------
10
+ u0 : float
11
+ The scalar part of the quaternion.
12
+ u1 : float
13
+ The first component of the vector part of the quaternion.
14
+ u2 : float
15
+ The second component of the vector part of the quaternion.
16
+ u3 : float
17
+ The third component of the vector part of the quaternion.
18
+ """
19
+ u0: float
20
+ u1: float
21
+ u2: float
22
+ u3: float
23
+
24
+
25
+ class Euler(NamedTuple):
26
+ """
27
+ A class to represent Euler angles.
28
+
29
+ Attributes:
30
+ rx (float): Rotation around the x-axis in radians.
31
+ ry (float): Rotation around the y-axis in radians.
32
+ rz (float): Rotation around the z-axis in radians.
33
+ """
34
+ rx: float
35
+ ry: float
36
+ rz: float
37
+
38
+
39
+ class Pos(NamedTuple):
40
+ """
41
+ Pose is a NamedTuple that represents a pose in 3D space.
42
+
43
+ Attributes:
44
+ x (float): The x coordinate.
45
+ y (float): The y coordinate.
46
+ z (float): The z coordinate
47
+ """
48
+ x: float
49
+ y: float
50
+ z: float
51
+
52
+
53
+ class Pose(NamedTuple):
54
+ """
55
+ A class to represent a 3D pose with x, y, and z coordinates.
56
+
57
+ Attributes:
58
+ pos (Position): The position component of the pose.
59
+ orient (Orientation): The orientation component of the pose.
60
+ euler (Euler): The Euler angles representing the orientation.
61
+ """
62
+ pos: Pos
63
+ orient: Orientation
64
+ euler: Euler
@@ -0,0 +1,538 @@
1
+ # Copyright 2022 Wason Technology LLC, Rensselaer Polytechnic Institute
2
+ #
3
+ # Licensed under the Apache License, Version 2.0 (the "License");
4
+ # you may not use this file except in compliance with the License.
5
+ # You may obtain a copy of the License at
6
+ #
7
+ # http://www.apache.org/licenses/LICENSE-2.0
8
+ #
9
+ # Unless required by applicable law or agreed to in writing, software
10
+ # distributed under the License is distributed on an "AS IS" BASIS,
11
+ # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12
+ # See the License for the specific language governing permissions and
13
+ # limitations under the License.
14
+
15
+ import socket
16
+ import select
17
+ import numpy as np
18
+ import errno
19
+ from typing import Tuple, NamedTuple, Any, Optional
20
+ from ABBRobotEGM._egm_protobuf import egm_pb2
21
+ from .abb_data import Pos, Orientation, Euler, Pose
22
+
23
+ # Constants
24
+ DEFAULT_PORT = 6510
25
+ BUFFER_SIZE = 65536
26
+ TIMEOUT = 0.5
27
+
28
+
29
+ class EGMHeader(NamedTuple):
30
+ """Represents EGM message header"""
31
+ seqno: int
32
+ tm: int
33
+ mtype: str
34
+
35
+
36
+ class EGMTimeStamp(NamedTuple):
37
+ """Represents PTP/IEEE-1588 timestamp."""
38
+ seconds: int
39
+ nanoseconds: int
40
+
41
+
42
+ class EGMClock(NamedTuple):
43
+ """Represents Unix timestamp."""
44
+ seconds: int
45
+ microseconds: int
46
+
47
+
48
+ class EGMRobotState(NamedTuple):
49
+ """Represents the state of the robot as received from EGM feedback."""
50
+ # Header information
51
+ header: EGMHeader
52
+
53
+ # Feedback state
54
+ joint_angles: np.array
55
+ cartesian: Optional[Pose]
56
+ external_axes: np.array
57
+ clock: Optional[Tuple[int, int]] # EgmClock (seconds, microseconds)
58
+ timestamp: Optional[Tuple[int, int]] # EgmTimestamp (seconds, nanoseconds)
59
+
60
+ # Planned state
61
+ joint_angles_planned: np.array
62
+ cartesian_planned: Optional[Pose]
63
+ external_axes_planned: np.array
64
+ planned_clock: Optional[Tuple[int, int]]
65
+ planned_timestamp: Optional[Tuple[int, int]]
66
+
67
+ # Motor and execution state
68
+ motors_on: bool
69
+ mci_state: str
70
+ mci_convergence_met: bool
71
+ rapid_running: bool
72
+
73
+ # Forces and motion
74
+ measured_force: np.array
75
+ utilization_rate: float
76
+ move_index: int
77
+
78
+ # Collision and diagnostics
79
+ collision_info: Any
80
+ test_signals: np.array
81
+
82
+ # RAPID interface
83
+ rapid_from_robot: np.array
84
+
85
+ # Additional data
86
+ torque_ref: np.array
87
+ robot_message: Any # Raw message for debugging
88
+
89
+
90
+ class EGM:
91
+ """
92
+ ABB EGM (Externally Guided Motion) client. EGM provides a real-time streaming connection to the robot using
93
+ UDP, typically at a rate of 250 Hz. The robot controller initiates the connection. The IP address and port of the
94
+ client must be configured on the robot controller side. The EGM client will send commands to the port it receives
95
+ packets from.
96
+
97
+ :param port: The port to receive UDP packets. Defaults to 6510
98
+ """
99
+
100
+ def __init__(self, port: int = DEFAULT_PORT):
101
+ self.socket = socket.socket(socket.AF_INET, socket.SOCK_DGRAM)
102
+ self.socket.bind(('', port))
103
+ self.send_sequence_number = 0
104
+ self.egm_addr = None
105
+ self.count = 0
106
+
107
+ def __enter__(self):
108
+ """Enter the context manager protocol."""
109
+ return self
110
+
111
+ def __exit__(self, exc_type, exc_val, exc_tb):
112
+ """Exit the context manager protocol."""
113
+ self.close()
114
+
115
+ def receive_from_robot(self, timeout: float = TIMEOUT) -> Tuple[bool, Optional[EGMRobotState]]:
116
+ """
117
+ Receive feedback from the robot. Specify an optional timeout. Returns a tuple with success and the current
118
+ robot state.
119
+
120
+ :param timeout: Timeout in seconds. May be zero to immediately return if there is no new data.
121
+ :return: Success and robot state as a tuple
122
+ """
123
+ try:
124
+ res = select.select([self.socket], [], [self.socket], timeout)
125
+ except select.error as err:
126
+ if err.args[0] == errno.EINTR:
127
+ return False, None
128
+ raise
129
+
130
+ if not res[0] and not res[2]:
131
+ return False, None
132
+
133
+ try:
134
+ buf, addr = self.socket.recvfrom(BUFFER_SIZE)
135
+ except socket.error:
136
+ self.egm_addr = None
137
+ return False, None
138
+
139
+ self.egm_addr = addr
140
+ robot_message = egm_pb2.EgmRobot()
141
+ robot_message.ParseFromString(buf)
142
+
143
+ state = self._parse_robot_message(robot_message)
144
+ return True, state
145
+
146
+ def _parse_robot_message(self, robot_message: Any) -> EGMRobotState:
147
+ """Parse the robot message and return the robot state."""
148
+ # Get header information
149
+ header = EGMHeader(
150
+ seqno=robot_message.header.seqno if robot_message.HasField('header') else 0,
151
+ tm=robot_message.header.tm if robot_message.HasField('header') else 0,
152
+ mtype=robot_message.header.mtype if robot_message.HasField('header') else "UNDEFINED"
153
+ )
154
+
155
+ # Get feedback data
156
+ joint_angles = self._get_joint_angles(robot_message)
157
+ cartesian = self._get_cartesian(robot_message)
158
+ external_axes = self._get_external_axes(robot_message)
159
+ clock, timestamp = self._get_timestamps(robot_message)
160
+
161
+ # Get planned data
162
+ joint_angles_planned = self._get_joint_angles_planned(robot_message)
163
+ cartesian_planned = self._get_cartesian_planned(robot_message)
164
+ external_axes_planned = self._get_external_axes_planned(robot_message)
165
+ planned_clock, planned_timestamp = self._get_planned_timestamps(robot_message)
166
+
167
+ # Get motor and execution state
168
+ motors_on = self._get_motors_on(robot_message)
169
+ mci_state = self._get_mci_state(robot_message)
170
+ mci_convergence_met = self._get_mci_convergence_met(robot_message)
171
+ rapid_running = self._get_rapid_running(robot_message)
172
+
173
+ # Get forces and motion data
174
+ measured_force = self._get_measured_force(robot_message)
175
+ utilization_rate = self._get_utilization_rate(robot_message)
176
+ move_index = self._get_move_index(robot_message)
177
+
178
+ # Get collision and diagnostics
179
+ collision_info = self._get_collision_info(robot_message)
180
+ test_signals = self._get_test_signals(robot_message)
181
+
182
+ # Get RAPID and torque data
183
+ rapid_from_robot = self._get_rapid_from_robot(robot_message)
184
+ torque_ref = self._get_torque_ref(robot_message)
185
+
186
+ return EGMRobotState(
187
+ header=header,
188
+ joint_angles=joint_angles,
189
+ cartesian=cartesian,
190
+ external_axes=external_axes,
191
+ clock=clock,
192
+ timestamp=timestamp,
193
+ joint_angles_planned=joint_angles_planned,
194
+ cartesian_planned=cartesian_planned,
195
+ external_axes_planned=external_axes_planned,
196
+ planned_clock=planned_clock,
197
+ planned_timestamp=planned_timestamp,
198
+ motors_on=motors_on,
199
+ mci_state=mci_state,
200
+ mci_convergence_met=mci_convergence_met,
201
+ rapid_running=rapid_running,
202
+ measured_force=measured_force,
203
+ utilization_rate=utilization_rate,
204
+ move_index=move_index,
205
+ collision_info=collision_info,
206
+ test_signals=test_signals,
207
+ rapid_from_robot=rapid_from_robot,
208
+ torque_ref=torque_ref,
209
+ robot_message=robot_message
210
+ )
211
+
212
+ def _get_joint_angles(self, robot_message: Any) -> np.array:
213
+ if robot_message.HasField('feedBack'):
214
+ return np.array(list(robot_message.feedBack.joints.joints))
215
+ return np.array([])
216
+
217
+ def _get_rapid_running(self, robot_message: Any) -> bool:
218
+ if robot_message.HasField('rapidExecState'):
219
+ return robot_message.rapidExecState.state == robot_message.rapidExecState.RAPID_RUNNING
220
+ return False
221
+
222
+ def _get_motors_on(self, robot_message: Any) -> bool:
223
+ if robot_message.HasField('motorState'):
224
+ return robot_message.motorState.state == robot_message.motorState.MOTORS_ON
225
+ return False
226
+
227
+ def _get_cartesian(self, robot_message: Any) -> Optional[Pose]:
228
+ if robot_message.HasField('feedBack') and robot_message.feedBack.HasField('cartesian'):
229
+ cart_p = robot_message.feedBack.cartesian.pos
230
+ cart_q = robot_message.feedBack.cartesian.orient
231
+ return Pose(
232
+ pos=Pos(cart_p.x, cart_p.y, cart_p.z),
233
+ orient=Orientation(cart_q.u0, cart_q.u1, cart_q.u2, cart_q.u3),
234
+ euler=Euler(0, 0, 0) # Assuming Euler angles are not provided in the message
235
+ )
236
+ return None
237
+
238
+ def _get_external_axes(self, robot_message: Any) -> np.array:
239
+ if robot_message.HasField('feedBack') and robot_message.feedBack.HasField('externalJoints'):
240
+ return np.array(list(robot_message.feedBack.externalJoints.joints))
241
+ return np.array([])
242
+
243
+ def _get_external_axes_planned(self, robot_message: Any) -> np.array:
244
+ if robot_message.HasField('planned') and robot_message.planned.HasField('externalJoints'):
245
+ return np.array(list(robot_message.planned.externalJoints.joints))
246
+ return np.array([])
247
+
248
+ def _get_joint_angles_planned(self, robot_message: Any) -> np.array:
249
+ if robot_message.HasField('planned') and robot_message.planned.HasField('joints'):
250
+ return np.array(list(robot_message.planned.joints.joints))
251
+ return np.array([])
252
+
253
+ def _get_cartesian_planned(self, robot_message: Any) -> Optional[Pose]:
254
+ if robot_message.HasField('planned') and robot_message.planned.HasField('cartesian'):
255
+ cart_p = robot_message.planned.cartesian.pos
256
+ cart_q = robot_message.planned.cartesian.orient
257
+ return Pose(
258
+ pos=Pos(cart_p.x, cart_p.y, cart_p.z),
259
+ orient=Orientation(cart_q.u0, cart_q.u1, cart_q.u2, cart_q.u3),
260
+ euler=Euler(0, 0, 0) # Assuming Euler angles are not provided in the message
261
+ )
262
+ return None
263
+
264
+ def _get_measured_force(self, robot_message: Any) -> np.array:
265
+ if robot_message.HasField('measuredForce'):
266
+ force_active = robot_message.measuredForce.fcActive if robot_message.measuredForce.HasField('fcActive') else True
267
+ if force_active:
268
+ return np.array(list(robot_message.measuredForce.force))
269
+ return np.array([])
270
+
271
+ def _get_move_index(self, robot_message: Any) -> Optional[int]:
272
+ if robot_message.HasField('moveIndex'):
273
+ return robot_message.moveIndex
274
+ return None
275
+
276
+ def _get_rapid_from_robot(self, robot_message: Any) -> np.array:
277
+ if robot_message.HasField('RAPIDfromRobot'):
278
+ return np.array(list(robot_message.RAPIDfromRobot.dnum))
279
+ return np.array([])
280
+
281
+ def _get_mci_state(self, robot_message: Any) -> Optional[str]:
282
+ if robot_message.HasField('mciState'):
283
+ return robot_message.mciState.state
284
+ return None
285
+
286
+ def _get_mci_convergence_met(self, robot_message: Any) -> Optional[bool]:
287
+ if robot_message.HasField('mciConvergenceMet'):
288
+ return robot_message.mciConvergenceMet
289
+ return None
290
+
291
+ def _get_test_signals(self, robot_message: Any) -> np.array:
292
+ if robot_message.HasField('testSignals'):
293
+ return np.array(list(robot_message.testSignals.signals))
294
+ return np.array([])
295
+
296
+ def _get_utilization_rate(self, robot_message: Any) -> Optional[float]:
297
+ if robot_message.HasField('utilizationRate'):
298
+ return robot_message.utilizationRate
299
+ return None
300
+
301
+ def _get_collision_info(self, robot_message: Any) -> Optional[Any]:
302
+ if robot_message.HasField('CollisionInfo'):
303
+ return robot_message.CollisionInfo
304
+ return None
305
+
306
+ def debug_print_robot_message(self, robot_message: Any):
307
+ """
308
+ Print the robot message for debugging purposes.
309
+
310
+ :param robot_message: The robot message to print
311
+ """
312
+ print(robot_message)
313
+
314
+ def send_to_robot(self, joint_angles: Optional[np.array] = None,
315
+ cartesian: Optional[Tuple[np.ndarray, np.ndarray]] = None,
316
+ speed_ref: np.array = None, external_joints: np.array = None,
317
+ external_joints_speed: np.array = None, rapid_to_robot: np.array = None, digital_signal_to_robot: bool = None) -> bool:
318
+ """
319
+ Send a command to robot. Returns False if no data has been received from the robot yet.
320
+ Either joint_angles or cartesian must be provided.
321
+
322
+ :param joint_angles: Joint angle command in degrees
323
+ :param cartesian: Tuple of (position, orientation) where:
324
+ - position is [x,y,z] in millimeters
325
+ - orientation is quaternion [w,x,y,z]
326
+ :param speed_ref: Speed reference for the joints
327
+ :param external_joints: External joints positions
328
+ :param external_joints_speed: External joints speed reference
329
+ :param rapid_to_robot: RAPID data to send to robot
330
+ :return: True if successful, False if no data received from robot yet
331
+ """
332
+ if not self.egm_addr:
333
+ return False
334
+
335
+ # if joint_angles is None and cartesian is None:
336
+ # raise ValueError("Either joint_angles or cartesian must be provided")
337
+
338
+ self.send_sequence_number += 1
339
+
340
+ if cartesian is not None:
341
+ # If cartesian is provided, use cartesian control
342
+ pos, orient = cartesian
343
+ sensor_message = self._create_sensor_message_cart(
344
+ pos, orient, speed_ref, external_joints, external_joints_speed, rapid_to_robot, digital_signal_to_robot
345
+ )
346
+ else:
347
+ # Use joint control
348
+ sensor_message = self._create_sensor_message(
349
+ joint_angles, speed_ref, external_joints, external_joints_speed, rapid_to_robot, digital_signal_to_robot
350
+ )
351
+
352
+ return self._send_message(sensor_message)
353
+
354
+ def _create_sensor_message(self, joint_angles: np.array, speed_ref: np.array, external_joints: np.array,
355
+ external_joints_speed: np.array, rapid_to_robot: np.array, digital_signal_to_robot: bool) -> Any:
356
+ """Create the sensor message to be sent to the robot."""
357
+ sensor_message = egm_pb2.EgmSensor()
358
+ header = sensor_message.header
359
+ header.mtype = egm_pb2.EgmHeader.MessageType.Value('MSGTYPE_CORRECTION')
360
+ header.seqno = self.send_sequence_number
361
+ self.send_sequence_number += 1
362
+
363
+ planned = sensor_message.planned
364
+ speed_ref_message = sensor_message.speedRef
365
+
366
+ if joint_angles is not None:
367
+ joint_angles = self._flatten_and_convert_to_list(joint_angles)
368
+ planned.joints.joints.extend(joint_angles)
369
+
370
+ if speed_ref is not None:
371
+ speed_ref = self._flatten_and_convert_to_list(speed_ref)
372
+ speed_ref_message.joints.joints.extend(speed_ref)
373
+
374
+ if external_joints is not None:
375
+ external_joints = self._flatten_and_convert_to_list(external_joints)
376
+ planned.externalJoints.joints.extend(external_joints)
377
+
378
+ if external_joints_speed is not None:
379
+ external_joints_speed = self._flatten_and_convert_to_list(external_joints_speed)
380
+ speed_ref_message.externalJoints.joints.extend(external_joints_speed)
381
+
382
+ if rapid_to_robot is not None:
383
+ rapid_to_robot = self._flatten_and_convert_to_list(rapid_to_robot)
384
+ sensor_message.RAPIDtoRobot.dnum.extend(rapid_to_robot)
385
+
386
+ if digital_signal_to_robot is not None:
387
+ sensor_message.RAPIDtoRobot.digVal = digital_signal_to_robot
388
+
389
+ return sensor_message
390
+
391
+ def _flatten_and_convert_to_list(self, array: np.array) -> list:
392
+ """Flatten the array and convert it to a list, ensuring homogeneous shape."""
393
+ try:
394
+ array = np.asarray(array, dtype=np.float64).flatten()
395
+ except ValueError:
396
+ raise ValueError("Input array has an inhomogeneous shape or contains non-numeric elements.")
397
+ return array.tolist()
398
+
399
+ def _send_message(self, message: Any) -> bool:
400
+ """Send the serialized message to the robot."""
401
+ buf = message.SerializeToString()
402
+ try:
403
+ self.socket.sendto(buf, self.egm_addr)
404
+ except socket.error:
405
+ return False
406
+ return True
407
+
408
+ def send_to_robot_cart(self, pos: np.ndarray, orient: np.ndarray, speed_ref: np.array = None,
409
+ external_joints: np.array = None, external_joints_speed: np.array = None,
410
+ rapid_to_robot: np.array = None, digital_signal_to_robot: bool = None) -> bool:
411
+ """
412
+ Send a cartesian command to robot. Returns False if no data has been received from the robot yet. The pose
413
+ is relative to the tool, workobject, and frame specified when the EGM operation is initialized. The EGM
414
+ operation must have been started with EGMActPose and EGMRunPose.
415
+
416
+ :param pos: The position of the TCP in millimeters [x,y,z]
417
+ :param orient: The orientation of the TCP in quaternions [w,x,y,z]
418
+ :return: True if successful, False if no data received from robot yet
419
+ """
420
+ if not self.egm_addr:
421
+ return False
422
+
423
+ self.send_sequence_number += 1
424
+ sensor_message = self._create_sensor_message_cart(pos, orient, speed_ref, external_joints,
425
+ external_joints_speed, rapid_to_robot, digital_signal_to_robot)
426
+ return self._send_message(sensor_message)
427
+
428
+ def _create_sensor_message_cart(self, pos: np.ndarray, orient: np.ndarray, speed_ref: np.array,
429
+ external_joints: np.array, external_joints_speed: np.array,
430
+ rapid_to_robot: np.array, digital_signal_to_robot: bool) -> Any:
431
+ """Create the sensor message with cartesian data to be sent to the robot."""
432
+ sensor_message = egm_pb2.EgmSensor()
433
+ header = sensor_message.header
434
+ header.mtype = egm_pb2.EgmHeader.MessageType.Value('MSGTYPE_CORRECTION')
435
+ header.seqno = self.send_sequence_number
436
+ self.send_sequence_number += 1
437
+
438
+ planned = sensor_message.planned
439
+ speed_ref_message = sensor_message.speedRef
440
+
441
+ if pos is not None and orient is not None:
442
+ planned.cartesian.pos.x = pos[0]
443
+ planned.cartesian.pos.y = pos[1]
444
+ planned.cartesian.pos.z = pos[2]
445
+ planned.cartesian.orient.u0 = orient[0]
446
+ planned.cartesian.orient.u1 = orient[1]
447
+ planned.cartesian.orient.u2 = orient[2]
448
+ planned.cartesian.orient.u3 = orient[3]
449
+
450
+ if speed_ref is not None:
451
+ speed_ref_message.cartesians.value.extend(list(np.array(speed_ref)))
452
+
453
+ if external_joints is not None:
454
+ planned.externalJoints.joints.extend(list(np.array(external_joints)))
455
+
456
+ if external_joints_speed is not None:
457
+ speed_ref_message.externalJoints.joints.extend(list(np.array(external_joints_speed)))
458
+
459
+ if rapid_to_robot is not None:
460
+ sensor_message.RAPIDtoRobot.dnum.extend(list(np.array(rapid_to_robot)))
461
+
462
+ if digital_signal_to_robot is not None:
463
+ sensor_message.RAPIDtoRobot.digVal = digital_signal_to_robot
464
+
465
+ return sensor_message
466
+
467
+ def send_to_robot_path_corr(self, pos: np.ndarray, age: float = 1) -> bool:
468
+ """
469
+ Send a path correction command. Returns False if no data has been received from the robot yet. The path
470
+ correction is a displacement [x,y,z] in millimeters in **path coordinates**. The displacement uses
471
+ "path coordinates", which relate the direction of movement of the end effector. See `CorrConn` command in
472
+ *Technical reference manual RAPID Instructions, Functions and Data types* for a detailed description of path
473
+ coordinates. The EGM operation must have been started with EGMActMove, and use EGMMoveL and EGMMoveC commands.
474
+
475
+ :param pos: The displacement in path coordinates in millimeters [x,y,z]
476
+ :return: True if successful, False if no data received from robot yet
477
+ """
478
+ self.send_sequence_number += 1
479
+ sensor_message = self._create_sensor_message_path_corr(pos, age)
480
+ return self._send_message(sensor_message)
481
+
482
+ def _create_sensor_message_path_corr(self, pos: np.ndarray, age: float) -> Any:
483
+ """Create the sensor message with path correction data to be sent to the robot."""
484
+ sensor_message = egm_pb2.EgmSensorPathCorr()
485
+ header = sensor_message.header
486
+ header.mtype = egm_pb2.EgmHeader.MessageType.Value('MSGTYPE_PATH_CORRECTION')
487
+ header.seqno = self.send_sequence_number
488
+ self.send_sequence_number += 1
489
+
490
+ path_corr = sensor_message.pathCorr
491
+ path_corr.pos.x = pos[0]
492
+ path_corr.pos.y = pos[1]
493
+ path_corr.pos.z = pos[2]
494
+ path_corr.age = age
495
+
496
+ return sensor_message
497
+
498
+ def _get_timestamps(self, robot_message: Any) -> Tuple[Optional[EGMClock], Optional[EGMTimeStamp]]:
499
+ clock = None
500
+ timestamp = None
501
+
502
+ if robot_message.HasField('feedBack'):
503
+ fb = robot_message.feedBack
504
+ if fb.HasField('time'):
505
+ clock = EGMClock(fb.time.sec, fb.time.usec)
506
+ if fb.HasField('timeStamp'):
507
+ timestamp = EGMTimeStamp(fb.timeStamp.sec, fb.timeStamp.nsec)
508
+
509
+ return clock, timestamp
510
+
511
+ def _get_planned_timestamps(self, robot_message: Any) -> Tuple[Optional[Tuple[int, int]], Optional[Tuple[int, int]]]:
512
+ """Get time and timestamp from planned data."""
513
+ clock = None
514
+ timestamp = None
515
+
516
+ if robot_message.HasField('planned'):
517
+ if robot_message.planned.HasField('time'):
518
+ clock = (robot_message.planned.time.sec,
519
+ robot_message.planned.time.usec)
520
+ if robot_message.planned.HasField('timeStamp'):
521
+ timestamp = (robot_message.planned.timeStamp.sec,
522
+ robot_message.planned.timeStamp.nsec)
523
+
524
+ return clock, timestamp
525
+
526
+ def _get_torque_ref(self, robot_message: Any) -> np.array:
527
+ """Get torque reference values."""
528
+ if robot_message.HasField('torqueRef'):
529
+ return np.array(list(robot_message.torqueRef.joints))
530
+ return np.array([])
531
+
532
+ def close(self):
533
+ """Close the connection to the robot."""
534
+ try:
535
+ self.socket.close()
536
+ self.socket = None
537
+ except socket.error:
538
+ pass
@@ -0,0 +1,138 @@
1
+ Metadata-Version: 2.2
2
+ Name: ABBRobotEGM
3
+ Version: 1.0.1
4
+ Summary: A Python library for real-time control and data streaming of ABB robots using EGM protocol, enabling high-frequency (250Hz) communication through UDP for industrial automation applications.
5
+ Home-page: https://github.com/FLo-ABB/ABB-EGM-Python
6
+ Author: Florian LOBERT
7
+ Classifier: Programming Language :: Python :: 3
8
+ Classifier: License :: OSI Approved :: Apache Software License
9
+ Classifier: Operating System :: OS Independent
10
+ Classifier: Intended Audience :: Developers
11
+ Requires-Python: >=3.6
12
+ Description-Content-Type: text/markdown
13
+ License-File: LICENSE
14
+ Requires-Dist: numpy
15
+ Requires-Dist: protobuf
16
+ Dynamic: author
17
+ Dynamic: classifier
18
+ Dynamic: description
19
+ Dynamic: description-content-type
20
+ Dynamic: home-page
21
+ Dynamic: requires-dist
22
+ Dynamic: requires-python
23
+ Dynamic: summary
24
+
25
+ # ABBRobotEGM
26
+
27
+ ![License](https://img.shields.io/badge/License-Apache%202.0-blue.svg)
28
+
29
+ `ABBRobotEGM` is a Python library for interfacing with ABB robots using Externally Guided Motion (EGM). This library provides real-time streaming communication with ABB robots at rates up to 250Hz using UDP. It's based on the official ABB EGM [documentation](https://github.com/FLo-ABB/ABB-EGM-Python/blob/main/doc/3HAC073318%20AM%20Externally%20Guided%20Motion%20RW7-en.pdf) and examples, and it's designed to be easy to use and to integrate with other systems.
30
+
31
+ ## Prerequisites
32
+
33
+ - Python 3.x
34
+ - ABB RobotWare 7.X (should work with 6.X with few modifications)
35
+ - ABB Robot with EGM option (3124-1 Externally Guided Motion)
36
+
37
+
38
+ ## Installation 🚀
39
+
40
+ ### Using pip 🐍
41
+
42
+ To install the library using pip, run the following command:
43
+
44
+ ```bash
45
+ pip install ABBRobotEGM
46
+ ```
47
+
48
+ ### Manual Installation 📦
49
+
50
+ To use this library in your project, first download the repository and place the `ABBRobotEGM` folder in your project's directory. You can then import the `EGM` class from this library to use it in your project.
51
+
52
+ ## Simple Examples
53
+
54
+ The repository includes several examples demonstrating different EGM functionalities. Inside each python example file, you can find the relative **RAPID** code that should be running on the robot controller.
55
+
56
+ ### Guidance Mode
57
+
58
+ #### 1. Joint
59
+
60
+ example_joint_guidance.py - Makes the first joint oscillate between -45° and +45°:
61
+
62
+ #### 2. Cartesian
63
+ example_pose_guidance.py - Makes the robot move in a circular pattern
64
+
65
+ ### Streaming Mode
66
+
67
+ #### 1. Joint Streaming
68
+ example_joint_stream.py - Streams robot joint positions :
69
+ ```python
70
+ from ABBRobotEGM import EGM
71
+
72
+ def main() -> None:
73
+ """
74
+ Example showing how to stream the robot's position.
75
+ Be sure the robot is running before running this script.
76
+ """
77
+ with EGM() as egm:
78
+ while True:
79
+ success, state = egm.receive_from_robot()
80
+ if not success:
81
+ print("Failed to receive from robot")
82
+ break
83
+ print(f"{state.clock[1]}, {state.joint_angles[0]}, {state.joint_angles[1]}, {state.joint_angles[2]}, {state.joint_angles[3]}, {state.joint_angles[4]}, {state.joint_angles[5]}")
84
+
85
+
86
+ if __name__ == "__main__":
87
+ main()
88
+
89
+ ```
90
+
91
+
92
+ #### 2. Cartesian Streaming
93
+ example_pos_stream.py - Streams robot cartesian position
94
+ ```python
95
+ from ABBRobotEGM import EGM
96
+
97
+ def main() -> None:
98
+ """
99
+ Example showing how to stream the robot's position.
100
+ Be sure the robot is running before running this script.
101
+ """
102
+ with EGM() as egm:
103
+ while True:
104
+ success, state = egm.receive_from_robot()
105
+ if not success:
106
+ print("Failed to receive from robot")
107
+ break
108
+ print(f"{state.clock[1]}, {state.cartesian.pos.x}, {state.cartesian.pos.y}, {state.cartesian.pos.z}")
109
+
110
+
111
+ if __name__ == "__main__":
112
+ main()
113
+ ```
114
+
115
+ ### 3. Data Exchange
116
+ example_table.py - Demonstrates exchanging data arrays with the robot
117
+
118
+ ## Complex Scenario
119
+ Example of a more complex scenario where the robot is scanning a surface giving in real time its tool center point position and correlating with a sensor reading. Rspag and python code available in *"scenario scan"* folder.
120
+
121
+ https://github.com/user-attachments/assets/03f151de-e098-4255-ac46-7dff42231071
122
+
123
+ ## Features 🚀
124
+
125
+ - Real-time communication at up to 250Hz
126
+ - Joint position control
127
+ - Cartesian position control
128
+ - Position streaming
129
+ - Path corrections
130
+ - RAPID data exchange
131
+ - External axis support
132
+ - Force measurement reading
133
+ - Comprehensive robot state feedback
134
+
135
+
136
+ ## Contributing 🤝
137
+
138
+ Contributions are welcome! Please feel free to submit pull requests.
@@ -0,0 +1,14 @@
1
+ LICENSE
2
+ MANIFEST.in
3
+ README.md
4
+ setup.py
5
+ src/ABBRobotEGM/__init__.py
6
+ src/ABBRobotEGM/abb_data.py
7
+ src/ABBRobotEGM/egm.py
8
+ src/ABBRobotEGM.egg-info/PKG-INFO
9
+ src/ABBRobotEGM.egg-info/SOURCES.txt
10
+ src/ABBRobotEGM.egg-info/dependency_links.txt
11
+ src/ABBRobotEGM.egg-info/requires.txt
12
+ src/ABBRobotEGM.egg-info/top_level.txt
13
+ src/ABBRobotEGM/_egm_protobuf/__init__.py
14
+ src/ABBRobotEGM/_egm_protobuf/egm_pb2.py
@@ -0,0 +1,2 @@
1
+ numpy
2
+ protobuf
@@ -0,0 +1 @@
1
+ ABBRobotEGM