-
Notifications
You must be signed in to change notification settings - Fork 2
/
supervisor_pickandplace.py
234 lines (207 loc) · 10.2 KB
/
supervisor_pickandplace.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
229
230
231
232
233
234
# Copyright 2021 CNRS - Airbus SAS
# Author: Florent Lamiraux, Joseph Mirabel
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions are
# met:
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in the
# documentation and/or other materials provided with the distribution.
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
# A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
# HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
# SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
# LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
# DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
# THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
# (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
# OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
# Theses variables are defined:
# - robot, a SoT device
# - simulateTorqueFeedbackForEndEffector, a boolean
import time
from agimus_sot.react import TaskFactory, localizeObjectOnLoopTransition
from agimus_sot.action import Action
from dynamic_graph.ros.ros_publish import RosPublish
Action.maxControlSqrNorm = 20
class CloseGripper(object):
timeout = 5
def __init__(self, sotrobot):
self.sotrobot = sotrobot
self.gripperCloseTopic = "/agimus/sot/gripper_status"
self.gripperClosePublisher = RosPublish("GripperClose")
self.gripperClosePublisher.add('boolean', 'gripperClosePublisher_', self.gripperCloseTopic)
self.gripperClosePublisher.signal('gripperClosePublisher_').value = True
def __call__(self):
ts = self.sotrobot.device.getTimeStep()
to = int(self.timeout / self.sotrobot.device.getTimeStep())
start_it = self.sotrobot.device.control.time
while True:
t = self.sotrobot.device.control.time
if t > start_it + to:
print("Failed to grasp")
return False, "Failed to grasp"
else:
self.gripperClosePublisher.signal('trigger').recompute(t)
time.sleep(ts)
time.sleep(3.)
return True, ""
class OpenGripper(object):
timeout = 5
def __init__(self, sotrobot):
self.sotrobot = sotrobot
self.gripperOpenTopic = "/agimus/sot/gripper_status"
self.gripperOpenPublisher = RosPublish("GripperOpen")
self.gripperOpenPublisher.add('boolean', 'gripperOpenPublisher_', self.gripperOpenTopic)
self.gripperOpenPublisher.signal('gripperOpenPublisher_').value = False
def __call__(self):
ts = self.sotrobot.device.getTimeStep()
to = int(self.timeout / self.sotrobot.device.getTimeStep())
start_it = self.sotrobot.device.control.time
while True:
t = self.sotrobot.device.control.time
if t > start_it + to:
print("Failed to grasp")
return False, "Failed to grasp"
else:
self.gripperOpenPublisher.signal('trigger').recompute(t)
time.sleep(ts)
time.sleep(3.)
return True, ""
# Action to be performed at start of pre-action of transition
# "ur3/gripper > part/handle_{} | f_12"
class ObjectLocalization(object):
timeout = 20
def __init__(self, sotrobot, factory, gripper, handle):
self.sotrobot = sotrobot
self.objectLocalization = factory.tasks.getGrasp(gripper, handle)\
['pregrasp'].objectLocalization
# JESSY 05/12 setVisualServoingMode to False.
self.objectLocalization.setVisualServoingMode(False)
self.handle = handle
self.localizationFailedTopic = "/agimus/status/localization_failed"
self.localizationFailedPublisher = RosPublish("localizationFailedPublisher")
self.localizationFailedPublisher.add('string', 'localizationFailedPublisher-'+handle, self.localizationFailedTopic)
self.localizationFailedPublisher.signal('localizationFailedPublisher-'+handle).value = ""
def __call__(self):
ts = self.sotrobot.device.getTimeStep()
to = int(self.timeout / self.sotrobot.device.getTimeStep())
start_it = self.sotrobot.device.control.time
while True:
t = self.sotrobot.device.control.time
if t > start_it + to:
print("Failed to perform object localization")
self.localizationFailedPublisher.signal('trigger').recompute(t)
return False, "Failed to perform object localization"
self.objectLocalization.trigger(t)
if self.objectLocalization.done.value:
print("Successfully performed object localization")
return True, ""
time.sleep(ts)
def wait():
print("Waiting 1 second")
time.sleep(1)
return True, ""
def makeSupervisorWithFactory(robot):
from agimus_sot import Supervisor
from agimus_sot.factory import Factory, Affordance
from agimus_sot.srdf_parser import parse_srdf, attach_all_to_link
import pinocchio
from rospkg import RosPack
rospack = RosPack()
if not hasattr(robot, "camera_frame"):
robot.camera_frame = "camera_color_optical_frame"
srdf = {}
# retrieve objects from ros param
robotDict = globalDemoDict["robots"]
if len(robotDict) != 1:
raise RuntimeError("One and only one robot is supported for now.")
objectDict = globalDemoDict["objects"]
objects = list(objectDict.keys())
# parse robot and object srdf files
srdfDict = dict()
for r, data in robotDict.items():
srdfDict[r] = parse_srdf(srdf = data["srdf"]["file"],
packageName = data["srdf"]["package"],
prefix=r)
for o, data in objectDict.items():
objectModel = pinocchio.buildModelFromUrdf\
(rospack.get_path(data["urdf"]["package"]) +
data["urdf"]["file"])
srdfDict[o] = parse_srdf(srdf = data["srdf"]["file"],
packageName = data["srdf"]["package"],
prefix=o)
attach_all_to_link(objectModel, "base_link", srdfDict[o])
grippers = list(globalDemoDict["grippers"])
handlesPerObjects = list()
contactPerObjects = list()
for o in objects:
handlesPerObjects.append(sorted(list(srdfDict[o]["handles"].keys())))
contactPerObjects.append(sorted(list(srdfDict[o]["contacts"].keys())))
for w in ["grippers", "handles","contacts"]:
srdf[w] = dict()
for k, data in srdfDict.items():
srdf[w].update(data[w])
supervisor = Supervisor(robot, prefix=list(robotDict.keys())[0])
factory = Factory(supervisor)
factory.tasks = TaskFactory(factory)
factory.parameters["period"] = 0.01 # TODO soon: robot.getTimeStep()
factory.parameters["simulateTorqueFeedback"] = simulateTorqueFeedbackForEndEffector
factory.parameters["addTracerToAdmittanceController"] = False
# factory.parameters["addTimerToSotControl"] = True
factory.setGrippers(grippers)
factory.setObjects(objects, handlesPerObjects, contactPerObjects)
from hpp.corbaserver.manipulation import Rule
factory.setupFrames(srdf["grippers"], srdf["handles"], robot)
for k in handlesPerObjects[0]:
factory.handleFrames[k].hasVisualTag = True
factory.generate()
supervisor.makeInitialSot()
g = factory.grippers[0]
for h in factory.handles:
transitionName_12 = '{} > {} | f_12'.format(g, h)
goalName = '{} grasps {}'.format(g, h)
# Add visual servoing in post actions of transtion 'g > h | f_12'
# visual servoing is deactivated by default at this step to avoid
# undesirable effects when grasping an object.
supervisor.postActions[transitionName_12][goalName].sot = \
supervisor.actions[transitionName_12].sot
# Add a pre-action to the pre-action of transition 'g > h | f_12'
# in order to perform object localization before starting the
# motion.
ol = ObjectLocalization(robot, factory, g, h)
supervisor.preActions[transitionName_12].preActions.append(ol)
# For calibration handles, relocalize in contact
# VISUAL Commented for visual servoing
#if h.find('calibration') != -1:
# supervisor.postActions[transitionName_12][goalName].preActions.\
# append(ol)
id = factory.handles.index(h)
transitionName_21 = '{} < {} | 0-{}_21'.format(g, h, id)
supervisor.preActions[transitionName_21].preActions.append(wait)
#localizeObjectOnLoopTransition(supervisor, factory.handles)
closeGripper = CloseGripper(robot)
openGripper = OpenGripper(robot)
#Grasp nuts
for i in range(92, 95):
#open gripper during pregrasp if it was previously closed
transitionName_12 = '{} > part/handle_{} | f_12'.format(g, i)
supervisor.actions[transitionName_12].preActions.append(openGripper)
transitionName_21 = '{} < part/handle_{} | 0-{}_21'.format(g, i, i)
supervisor.actions[transitionName_21].preActions.append(closeGripper)
#Release on screws
for i in range(68, 92):
#close gripper during pregrasp if it was previously oppened
transitionName_12 = '{} > part/handle_{} | f_12'.format(g, i)
supervisor.actions[transitionName_12].preActions.append(closeGripper)
transitionName_21 = '{} < part/handle_{} | 0-{}_21'.format(g, i, i)
supervisor.actions[transitionName_21].preActions.append(openGripper)
return factory, supervisor
# Use service /agimus/sot/set_base_pose to set initial config
factory, supervisor = makeSupervisorWithFactory(robot)
supervisor.plugTopicsToRos()
supervisor.plugSot("")