-
Notifications
You must be signed in to change notification settings - Fork 0
/
calibration.py
303 lines (280 loc) · 13.1 KB
/
calibration.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
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
# Copyright 2021 CNRS - Airbus SAS
# Author: Florent Lamiraux
#
# 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.
import os
import yaml
from csv import reader
import numpy as np
import eigenpy, pinocchio, hpp.rostools, hppfcl, numpy as np
from pinocchio import SE3, exp3, RobotWrapper, forwardKinematics, Quaternion
from agimus_demos.calibration import HandEyeCalibration as Parent
from tools_hpp import PathGenerator, RosInterface
from hpp import Transform
from hpp.corbaserver.manipulation import Constraints, SecurityMargins
## Hand-eye calibration
#
# This class provides methods to generate configurations where the robot
# camera looks at the center of a Chessboard in order to perform hand eye
# calibration.
#
# To play the paths on the robot and collect data, see play_path.py in this
# directory.
class Calibration(Parent):
chessboardCenter = (0, 0, 1.41)
# to aim at the center of the plaque with tubes, use
# chessboardCenter = (0, 0, 1.17)
# Number of configurations to generate for calibration
nbConfigs = 10
def __init__(self, ps, graph, factory):
super(Calibration, self).__init__(ps, graph)
self.factory = factory
Parent.transition = 'go-look-at-cb'
def generateValidConfigs(self, q0, n, m, M):
robot = self.ps.robot
graph = self.graph
result = list()
i = 0
while i < n:
q = robot.shootRandomConfig()
res, q1, err = graph.generateTargetConfig('go-look-at-cb', q0, q)
if not res: continue
# Check that coordinate of chessboard center along z is between
# m and M.
robot.setCurrentConfig(q1)
wMc = Transform(robot.getLinkPosition\
('ur10e/camera_color_optical_frame'))
wMp = Transform(robot.getLinkPosition('part/base_link'))
# Position of chessboard center in world frame
c = wMp.transform(np.array(self.chessboardCenter))
# Position of chessboard center in camera frame
c1 = wMc.inverse().transform(c)
if not (m < c1[2] and c1[2] < M): continue
res, msg = robot.isConfigValid(q1)
if res:
result.append(q1)
i += 1
return result
def addStateToConstraintGraph(self):
if 'look-at-cb' in self.graph.nodes.keys():
return
ps = self.ps; graph = self.graph
ps.createPositionConstraint\
('look-at-cb', 'ur10e/camera_color_optical_frame', 'part/base_link',
(0, 0, 0), self.chessboardCenter,
(True, True, False))
ps.createTransformationConstraint('placement/complement', '',
'part/root_joint',
[0,0,0,0, 0, 0, 1],
[True, True, True, True, True, True,])
ps.setConstantRightHandSide('placement/complement', False)
graph.createNode(['look-at-cb'])
graph.createEdge('free', 'look-at-cb', 'go-look-at-cb', 1,
'free')
graph.createEdge('look-at-cb', 'free', 'stop-looking-at-cb', 1,
'free')
graph.addConstraints(node='look-at-cb',
constraints = Constraints(numConstraints=['look-at-cb']))
graph.addConstraints(edge='go-look-at-cb',
constraints = Constraints(numConstraints=['placement/complement']))
graph.addConstraints(edge='stop-looking-at-cb',
constraints = Constraints(numConstraints=['placement/complement']))
self.factory.generate()
sm = SecurityMargins(ps, self.factory, ["ur10e", "part"])
sm.setSecurityMarginBetween("ur10e", "ur10e", 0.0)
sm.setSecurityMarginBetween("ur10e", "part", 0.015)
sm.defaultMargin = 0.01
sm.apply()
graph.initialize()
# Generate calibration configs and integrate them in a roadmap
#
# The number of configurations to generate is given by member
# nbConfigs.
#
# After building a roadmap with those configurations, if all of
# them are not in the same connected component, add random
# configurations to the roadmap and add edges between those configurations
# and previously existing configurations.
def generateConfigurationsAndPaths(self, q_init, filename = None):
ri = RosInterface(self.ps.robot)
if filename:
self.calibConfigs = self.readConfigsInFile(filename)
else:
self.calibConfigs = self.generateValidConfigs\
(q_init, self.nbConfigs, .3, .5)
finished = False
configs = [q_init] + self.calibConfigs
# save transition
transition = self.transition
self.setTransition("Loop | f")
for q in configs:
res, msg = self.pathValidation.validateConfiguration(q)
if not res:
print (f"{q} is not valid")
return
res, err = self.graph.getConfigErrorForEdgeLeaf("Loop | f", q_init,
q)
if not res:
print(f"{q} is not reachable from q_init")
return
while not finished:
self.buildRoadmap(configs)
# find connected component of q_init
for i in range(self.ps.numberConnectedComponents()):
cc = self.ps.nodesConnectedComponent(i)
if not q_init in cc:
continue
print(f'number of nodes in q_init connected component: {len(cc)}')
# From here on, q_init is in cc
finished = True
count = 0
for q in self.calibConfigs:
if q in cc:
count +=1
if 2*count < len(self.calibConfigs): finished = False
# if half of the configurations are in the same connected component,
# get out of the while loop
if finished: break
# Otherwise generate another batch of random configurations
configs += self.shootRandomConfigs(q_init, 10)
self.buildRoadmap(configs, len(configs) - 10)
self.setTransition(transition)
configs = self.orderConfigurations([q_init] + self.calibConfigs)
self.visitConfigurations([q_init] + self.calibConfigs)
# Generate a csv file with the following data for each configuration:
# x, y, z, phix, phiy, phiz,
# ur10e/shoulder_pan_joint, ur10e/shoulder_lift_joint, ur10e/elbow_joint,
# ur10e/wrist_1_joint, ur10e/wrist_2_joint, ur10e/wrist_3_joint
# corresponding to the pose of the camera in the world frame (orientation in
# roll, pitch, yaw), and the joints angles of the robot.
#
# maxIndex is the maximal index of the input files:
# configuration_{i}, i<=maxIndex,
# pose_cPo_{i}.yaml, i<=maxIndex.
def generateDataForFigaroh(robot, input_directory, output_file, maxIndex):
# Use reference pose of chessboard. Note that this is the pose of the
# frame extracted from pose computation top left part of the chessboard
wMo = SE3(translation=np.array([1.28, 0.108, 1.4775]),
rotation = np.array([[0,0,1],[-1,0,0],[0,-1,0]]))
# create a pinocchio model from the Robot.urdfString
with open('/tmp/robot.urdf', 'w') as f:
f.write(robot.urdfString)
pinRob = RobotWrapper()
pinRob.initFromURDF('/tmp/robot.urdf')
# get camera frame id
camera_frame_id = pinRob.model.getFrameId('camera_color_optical_frame')
with open(output_file, 'w') as f:
# write header line in output file
f.write('x1,y1,z1,phix1,phiy1,phiz1,shoulder_pan_joint,shoulder_lift_joint,elbow_joint,wrist_1_joint,wrist_2_joint,wrist_3_joint\n')
count = 1
while count <= maxIndex:
poseFile = os.path.join(input_directory, f'pose_cPo_{count}.yaml')
configFile = os.path.join(input_directory, f'configuration_{count}')
try:
f1 = open(poseFile, 'r')
d = yaml.safe_load(f1)
f1.close()
f1 = open(configFile, 'r')
config = f1.readline()
f1.close()
cMo_tuple = list(zip(*d['data']))[0]
trans = np.array(cMo_tuple[:3])
rot = exp3(np.array(cMo_tuple[3:]))
cMo = SE3(translation = trans, rotation = rot)
oMc = cMo.inverse()
wMc = wMo * oMc
line = ""
# write camera pose
for i in range(3):
line += f'{wMc.translation[i]},'
rpy = pinocchio.rpy.matrixToRpy(wMc.rotation)
for i in range(3):
line += f'{rpy[i]},'
# write configuration
line += config
f.write(line)
except FileNotFoundError as exc:
print(f'{poseFile} does not exist')
count+=1
def readDataFromFigaroh(filename, q0):
with open(filename, 'r') as f:
configurations = list()
wMcs = list()
r = reader(f)
for i, line in enumerate(r):
if i == 0: continue
xyz = list(map(float, line[0:3])); rpy = list(map(float, line[3:6]))
wMc = SE3(translation = np.array(xyz),
rotation = pinocchio.rpy.rpyToMatrix(np.array(rpy)))
wMcs.append(wMc)
# read robot configuration in csv file
q = list(map(float, line[6:]))
# append configuration of the plank
q += q0[6:]
configurations.append(q)
return configurations, wMcs
def displayPose(v, nodeName, wMc):
if not nodeName in v.client.gui.getNodeList():
v.client.gui.addXYZaxis(nodeName, [1,1,1,1], 0.015, 0.1)
pose = list(wMc.translation)
pose += list(Quaternion(wMc.rotation).coeffs())
v.client.gui.applyConfiguration(nodeName, pose)
v.client.gui.refresh()
# Read configurations and cMo in files and display corresponding pose
# in gepetto-gui
def checkData(robot, v, figaroh_csv_file, q_init):
view_from_camera = False
configurations, wMcs = readDataFromFigaroh(figaroh_csv_file, q_init)
for q, wMc in zip(configurations, wMcs):
displayPose(v, 'robot/chessboard', wMc)
if view_from_camera:
ql = list(wMc.translation)
ql += list((Quaternion(wMc.rotation)*
Quaternion(np.array([0,1,0,0]))).coeffs())
v.client.gui.setCameraTransform('scene_hpp_', ql)
v(q)
print('Check pose of camera and press enter')
input()
def computeCameraPose(mMe, eMc, eMc_measured):
# we wish to compute a new position mMe_new of ref_camera_link in
# ur10e_d435_mount_link in such a way that
# - eMc remains the same (we assume the camera is well calibrated),
# - mMc = mMe_new * eMc = mMe * eMc_measured
# Thus
# mMe_new = mMe*eMc_measured*eMc.inverse()
return mMe*eMc_measured*eMc.inverse()
# # Current position of ref_camera_link in ur10e_d435_mount_link
# mMe = pinocchio.SE3(translation=np.array([0.000, 0.117, -0.010]),
# quat = eigenpy.Quaternion(np.array(
# [-0.341, -0.340, -0.619, 0.620])))
# # Current position of camera_color_optical_frame in ref_camera_link
# eMc = pinocchio.SE3(translation=np.array([0.011, 0.033, 0.013]),
# quat = eigenpy.Quaternion(np.array(
# [-0.500, 0.500, -0.500, 0.500])))
# # Measured position of camera_optical_frame in ref_camera_link from calibration
# eMc_measured = pinocchio.SE3(translation=np.array(
# [0.009813399648, 0.03326932627, 0.01378242934]),
# quat = eigenpy.Quaternion(np.array(
# [-0.498901464, 0.5012362124, -0.4974698347, 0.5023776988])))
# #new position mMe_new of ref_camera_link in ur10e_d435_mount_link
# mMe_new = computeCameraPose(mMe, eMc, eMc_measured)
# xyz = mMe_new.translation
# rpy = pinocchio.rpy.matrixToRpy(mMe_new.rotation)