/
client.py
228 lines (180 loc) · 8.16 KB
/
client.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
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
from __future__ import absolute_import
from __future__ import division
from __future__ import print_function
from compas_fab.backends.exceptions import BackendFeatureNotSupportedError
def forward_docstring(backend_feature):
def dec(obj):
obj.__doc__ = backend_feature.__dict__[obj.__name__].__doc__
return obj
return dec
class ClientInterface(object):
"""Interface for all backend clients. Forwards all planning services and
planning scene management to the planner.
"""
def __init__(self):
self.planner = PlannerInterface(self)
# self.control = ControlInterface()
# ==========================================================================
# planning services
# ==========================================================================
def inverse_kinematics(self, *args, **kwargs):
"""Forwards call to appropriate method in the planner."""
return self.planner.inverse_kinematics(*args, **kwargs)
def forward_kinematics(self, *args, **kwargs):
"""Forwards call to appropriate method in the planner."""
return self.planner.forward_kinematics(*args, **kwargs)
def plan_cartesian_motion(self, *args, **kwargs):
"""Forwards call to appropriate method in the planner."""
return self.planner.plan_cartesian_motion(*args, **kwargs)
def plan_motion(self, *args, **kwargs):
"""Forwards call to appropriate method in the planner."""
return self.planner.plan_motion(*args, **kwargs)
# ==========================================================================
# collision objects and planning scene
# ==========================================================================
def get_planning_scene(self, *args, **kwargs):
"""Forwards call to appropriate method in the planner."""
return self.planner.get_planning_scene(*args, **kwargs)
def reset_planning_scene(self, *args, **kwargs):
"""Forwards call to appropriate method in the planner."""
return self.planner.reset_planning_scene(*args, **kwargs)
def add_collision_mesh(self, *args, **kwargs):
"""Forwards call to appropriate method in the planner."""
return self.planner.add_collision_mesh(*args, **kwargs)
def remove_collision_mesh(self, *args, **kwargs):
"""Forwards call to appropriate method in the planner."""
return self.planner.remove_collision_mesh(*args, **kwargs)
def append_collision_mesh(self, *args, **kwargs):
"""Forwards call to appropriate method in the planner."""
return self.planner.append_collision_mesh(*args, **kwargs)
def add_attached_collision_mesh(self, *args, **kwargs):
"""Forwards call to appropriate method in the planner."""
return self.planner.add_attached_collision_mesh(*args, **kwargs)
def remove_attached_collision_mesh(self, *args, **kwargs):
"""Forwards call to appropriate method in the planner."""
return self.planner.remove_attached_collision_mesh(*args, **kwargs)
# # ==========================================================================
# # executing
# # ==========================================================================
#
# def execute_joint_trajectory(self, *args, **kwargs):
# self.control.execute_joint_trajectory(*args, **kwargs)
#
# def follow_joint_trajectory(self, *args, **kwargs):
# self.control.follow_joint_trajectory(*args, **kwargs)
#
# def get_configuration(self, *args, **kwargs):
# self.control.get_configuration(*args, **kwargs)
#
#
# class ControlInterface(object):
# def execute_joint_trajectory(self, *args, **kwargs):
# raise NotImplementedError('Assigned control does not have this feature.')
#
# def follow_joint_trajectory(self, *args, **kwargs):
# raise NotImplementedError('Assigned control does not have this feature.')
#
# def get_configuration(self, *args, **kwargs):
# raise NotImplementedError('Assigned control does not have this feature.')
class PlannerInterface(object):
"""Interface for all planners associated with a backend client. Provides default
behavior for all planning services and planning scene management methods. To be
use in conjunction with backend feature interfaces.
"""
def __init__(self, client):
super(PlannerInterface, self).__init__()
self.client = client
# ==========================================================================
# planning services
# ==========================================================================
def inverse_kinematics(self, *args, **kwargs):
"""Default method for planner.
Raises
------
BackendFeatureNotSupportedError
Planner does not have this feature.
"""
raise BackendFeatureNotSupportedError("Assigned planner does not have this feature.")
def forward_kinematics(self, *args, **kwargs):
"""Default method for planner.
Raises
------
BackendFeatureNotSupportedError
Planner does not have this feature.
"""
raise BackendFeatureNotSupportedError("Assigned planner does not have this feature.")
def plan_motion(self, *args, **kwargs):
"""Default method for planner.
Raises
------
BackendFeatureNotSupportedError
Planner does not have this feature.
"""
raise BackendFeatureNotSupportedError("Assigned planner does not have this feature.")
def plan_cartesian_motion(self, *args, **kwargs):
"""Default method for planner.
Raises
------
BackendFeatureNotSupportedError
Planner does not have this feature.
"""
raise BackendFeatureNotSupportedError("Assigned planner does not have this feature.")
# ==========================================================================
# collision objects and planning scene
# ==========================================================================
def get_planning_scene(self, *args, **kwargs):
"""Default method for planner.
Raises
------
BackendFeatureNotSupportedError
Planner does not have this feature.
"""
raise BackendFeatureNotSupportedError("Assigned planner does not have this feature.")
def reset_planning_scene(self, *args, **kwargs):
"""Default method for planner.
Raises
------
BackendFeatureNotSupportedError
Planner does not have this feature.
"""
raise BackendFeatureNotSupportedError("Assigned planner does not have this feature.")
def add_collision_mesh(self, *args, **kwargs):
"""Default method for planner.
Raises
------
BackendFeatureNotSupportedError
Planner does not have this feature.
"""
raise BackendFeatureNotSupportedError("Assigned planner does not have this feature.")
def remove_collision_mesh(self, *args, **kwargs):
"""Default method for planner.
Raises
------
BackendFeatureNotSupportedError
Planner does not have this feature.
"""
raise BackendFeatureNotSupportedError("Assigned planner does not have this feature.")
def append_collision_mesh(self, *args, **kwargs):
"""Default method for planner.
Raises
------
BackendFeatureNotSupportedError
Planner does not have this feature.
"""
raise BackendFeatureNotSupportedError("Assigned planner does not have this feature.")
def add_attached_collision_mesh(self, *args, **kwargs):
"""Default method for planner.
Raises
------
BackendFeatureNotSupportedError
Planner does not have this feature.
"""
raise BackendFeatureNotSupportedError("Assigned planner does not have this feature.")
def remove_attached_collision_mesh(self, *args, **kwargs):
"""Default method for planner.
Raises
------
BackendFeatureNotSupportedError
Planner does not have this feature.
"""
raise BackendFeatureNotSupportedError("Assigned planner does not have this feature.")