-
Notifications
You must be signed in to change notification settings - Fork 33
/
robot_library.py
180 lines (140 loc) · 5.84 KB
/
robot_library.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
from __future__ import absolute_import
from __future__ import division
from __future__ import print_function
from compas_robots import RobotModel
from compas_robots.resources import LocalPackageMeshLoader
import compas_fab
from .robot import Robot
from .semantics import RobotSemantics
__all__ = [
"RobotLibrary",
]
class RobotLibrary(object):
"""A collection of built-in robots that can be used for testing and example purposes.
The :class:`compas_fab.robots.Robot` objects created by the factory methods
can be used to write examples, so that the example code can stay short.
The robots are loaded from URDF, SRDF and local mesh files.
The resulting robot object
contains the robot model, semantics, visual and collision meshes for the links.
Examples
--------
>>> from compas_fab.robots import RobotLibrary
>>> robot = RobotLibrary.ur5()
>>> robot.name
'ur5_robot'
"""
@classmethod
def _load_library_model(
cls, urdf_filename, srdf_filename, local_package_mesh_folder, client=None, load_geometry=True
):
"""Convenience method for loading robot from local cache directory."""
model = RobotModel.from_urdf_file(urdf_filename)
semantics = RobotSemantics.from_srdf_file(srdf_filename, model)
if load_geometry:
loader = LocalPackageMeshLoader(compas_fab.get(local_package_mesh_folder), "")
model.load_geometry(loader)
robot = Robot(model, semantics=semantics)
if client:
robot.client = client
return robot
@classmethod
def rfl(cls, client=None, load_geometry=True):
"""Create and return the RFL robot with 4 ABB irb 4600 and twin-gantry setup.
The returned :class:`compas_fab.robots.Robot` object contains the robot model and semantics.
Parameters
----------
client: object
Backend client. Default is `None`.
load_geometry: bool, optional
Default is `True`, which means that the geometry is loaded.
`False` can be used to speed up the creation of the robot.
Returns
-------
:class:`compas_fab.robots.Robot`
Newly created instance of the robot.
"""
robot = cls._load_library_model(
urdf_filename=compas_fab.get("robot_library/rfl/urdf/robot_description.urdf"),
srdf_filename=compas_fab.get("robot_library/rfl/robot_description_semantic.srdf"),
local_package_mesh_folder="robot_library/rfl",
client=client,
load_geometry=load_geometry,
)
return robot
@classmethod
def ur5(cls, client=None, load_geometry=True):
"""Returns a UR5 robot.
The returned :class:`compas_fab.robots.Robot` object contains the robot model and semantics.
Parameters
----------
client: object
Backend client. Default is `None`.
load_geometry: bool, optional
Default is `True`, which means that the geometry is loaded.
`False` can be used to speed up the creation of the robot.
Returns
-------
:class:`compas_fab.robots.Robot`
Newly created instance of the robot.
"""
robot = cls._load_library_model(
urdf_filename=compas_fab.get("robot_library/ur5_robot/urdf/robot_description.urdf"),
srdf_filename=compas_fab.get("robot_library/ur5_robot/robot_description_semantic.srdf"),
local_package_mesh_folder="robot_library/ur5_robot",
client=client,
load_geometry=load_geometry,
)
return robot
@classmethod
def ur10e(cls, client=None, load_geometry=True):
"""Returns a UR10e robot.
The returned :class:`compas_fab.robots.Robot` object contains the robot model and semantics.
Parameters
----------
client: object
Backend client. Default is `None`.
load_geometry: bool, optional
Default is `True`, which means that the geometry is loaded.
`False` can be used to speed up the creation of the robot.
Returns
-------
:class:`compas_fab.robots.Robot`
Newly created instance of the robot.
"""
robot = cls._load_library_model(
urdf_filename=compas_fab.get("robot_library/ur10e_robot/urdf/robot_description.urdf"),
srdf_filename=compas_fab.get("robot_library/ur10e_robot/robot_description_semantic.srdf"),
local_package_mesh_folder="robot_library/ur10e_robot",
client=client,
load_geometry=load_geometry,
)
return robot
@classmethod
def abb_irb4600_40_255(cls, client=None, load_geometry=True):
"""Returns a ABB irb4600-40/2.55 robot.
The returned :class:`compas_fab.robots.Robot` object contains the robot model and semantics.
Parameters
----------
client: object
Backend client. Default is `None`.
load_geometry: bool, optional
Default is `True`, which means that the geometry is loaded.
`False` can be used to speed up the creation of the robot.
Returns
-------
:class:`compas_fab.robots.Robot`
Newly created instance of the robot.
"""
robot = cls._load_library_model(
urdf_filename=compas_fab.get("robot_library/abb_irb4600_40_255/urdf/robot_description.urdf"),
srdf_filename=compas_fab.get("robot_library/abb_irb4600_40_255/robot_description_semantic.srdf"),
local_package_mesh_folder="robot_library/abb_irb4600_40_255",
client=client,
load_geometry=load_geometry,
)
return robot
if __name__ == "__main__":
robot = RobotLibrary.rfl(load_geometry=True)
robot.info()
robot = RobotLibrary.ur5(load_geometry=True)
robot.info()