forked from Abishalini/moveit_calibration
-
Notifications
You must be signed in to change notification settings - Fork 3
/
handeye_solver_default.cpp
435 lines (402 loc) · 15.9 KB
/
handeye_solver_default.cpp
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
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2019, Intel Corporation.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * 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.
* * Neither the name of Willow Garage nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* 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 OWNER 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.
*********************************************************************/
/* Author: Yu Yan */
#include <moveit/handeye_calibration_solver/handeye_solver_default.h>
#include <rclcpp/rclcpp.hpp>
#if PY_MAJOR_VERSION >= 3
#define PyInt_AsLong PyLong_AsLong
#define PyString_FromString PyUnicode_FromString
#endif
namespace moveit_handeye_calibration
{
void HandEyeSolverDefault::initialize()
{
solver_names_ = { "Daniilidis1999", "ParkBryan1994", "TsaiLenz1989" };
camera_robot_pose_ = Eigen::Isometry3d::Identity();
}
const std::vector<std::string>& HandEyeSolverDefault::getSolverNames() const
{
return solver_names_;
}
const Eigen::Isometry3d& HandEyeSolverDefault::getCameraRobotPose() const
{
return camera_robot_pose_;
}
// TODO: HandEyeSolverDefault::solve() needs to be ported to ROS
bool HandEyeSolverDefault::solve(const std::vector<Eigen::Isometry3d>& effector_wrt_world,
const std::vector<Eigen::Isometry3d>& object_wrt_sensor, SensorMountType setup,
const std::string& solver_name, std::string* error_message)
{
std::string local_error_message;
if (!error_message)
{
error_message = &local_error_message;
}
// Check the size of the two sets of pose sample equal
if (effector_wrt_world.size() != object_wrt_sensor.size())
{
*error_message = "The sizes of the two input pose sample vectors are not equal: effector_wrt_world.size() = " +
std::to_string(effector_wrt_world.size()) +
" and object_wrt_sensor.size() == " + std::to_string(object_wrt_sensor.size());
RCLCPP_ERROR_STREAM(LOGGER_CALIBRATION_SOLVER, *error_message);
return false;
}
auto it = std::find(solver_names_.begin(), solver_names_.end(), solver_name);
if (it == solver_names_.end())
{
*error_message = "Unknown handeye solver name: " + solver_name;
RCLCPP_ERROR_STREAM(LOGGER_CALIBRATION_SOLVER, *error_message);
return false;
}
char program_name[7] = "python";
#if PY_MAJOR_VERSION >= 3
Py_SetProgramName(Py_DecodeLocale(program_name, NULL));
#else
Py_SetProgramName(program_name);
#endif
static bool numpy_loaded{ false };
if (!numpy_loaded) // Py_Initialize() can only be called once when numpy is
// loaded, otherwise will segfault
{
Py_Initialize();
atexit(Py_Finalize);
numpy_loaded = true;
}
RCLCPP_DEBUG_STREAM(LOGGER_CALIBRATION_SOLVER, "Python C API start");
// Load numpy c api
if (_import_array() < 0)
{
*error_message = "Error importing numpy";
RCLCPP_ERROR_STREAM(LOGGER_CALIBRATION_SOLVER, *error_message);
return false;
}
PyObject *python_name, *python_module, *python_class, *python_instance, *python_func_add_sample, *python_func_solve;
PyObject *python_args, *python_value;
// Import handeye.calibrator python module
python_name = PyString_FromString("handeye.calibrator");
python_module = PyImport_Import(python_name);
Py_DECREF(python_name);
if (!python_module)
{
*error_message = "Failed to load python module: handeye.calibrator";
RCLCPP_ERROR_STREAM(LOGGER_CALIBRATION_SOLVER, *error_message);
PyErr_Print();
return false;
}
// Find handeye.calibrator.HandEyeCalibrator class
python_class = PyObject_GetAttrString(python_module, "HandEyeCalibrator");
Py_DECREF(python_module);
if (!python_class || !PyCallable_Check(python_class))
{
*error_message = "Can't find \"HandEyeCalibrator\" python class";
RCLCPP_ERROR_STREAM(LOGGER_CALIBRATION_SOLVER, *error_message);
PyErr_Print();
return false;
}
// Parse sensor mount type
python_value = PyString_FromString("");
if (setup == EYE_TO_HAND)
python_value = PyString_FromString("Fixed");
else if (setup == EYE_IN_HAND)
python_value = PyString_FromString("Moving");
if (!python_value)
{
*error_message = "Can't create sensor mount type python value";
RCLCPP_ERROR_STREAM(LOGGER_CALIBRATION_SOLVER, *error_message);
Py_DECREF(python_class);
PyErr_Print();
return false;
}
// Create handeye.calibrator.HandEyeCalibrator instance
python_args = PyTuple_New(1);
PyTuple_SetItem(python_args, 0, python_value);
if (!python_args)
{
*error_message = "Can't build python arguments";
RCLCPP_ERROR_STREAM(LOGGER_CALIBRATION_SOLVER, *error_message);
Py_DECREF(python_class);
PyErr_Print();
return false;
}
python_instance = PyEval_CallObject(python_class, python_args);
Py_DECREF(python_args);
Py_DECREF(python_class);
if (!python_instance)
{
*error_message = "Can't create \"HandEyeCalibrator\" python instance";
RCLCPP_ERROR_STREAM(LOGGER_CALIBRATION_SOLVER, *error_message);
PyErr_Print();
return false;
}
// Find handeye.calibrator.HandEyeCalibrator.add_sample method
python_func_add_sample = PyObject_GetAttrString(python_instance, "add_sample");
if (!python_func_add_sample || !PyCallable_Check(python_func_add_sample))
{
*error_message = "Can't find 'add_sample' method";
RCLCPP_ERROR_STREAM(LOGGER_CALIBRATION_SOLVER, *error_message);
Py_DECREF(python_instance);
PyErr_Print();
return false;
}
// Add sample poses to handeye.calibrator.HandEyeCalibrator instance
size_t number_of_poses = effector_wrt_world.size();
PyArrayObject *numpy_arg_eef_wrt_base[number_of_poses], *numpy_arg_obj_wrt_sensor[number_of_poses];
PyObject *python_array_eef_wrt_base[number_of_poses], *python_array_obj_wrt_sensor[number_of_poses];
PyObject* python_args_sample[number_of_poses];
npy_intp dims[2]{ TRANSFORM_MATRIX_DIMENSION, TRANSFORM_MATRIX_DIMENSION };
const int number_of_dims{ 2 };
// Using C array to store the pyarray data, which will be automatically freed
double c_arr_eef_wrt_world[number_of_poses][TRANSFORM_MATRIX_DIMENSION][TRANSFORM_MATRIX_DIMENSION];
double c_arr_obj_wrt_sensor[number_of_poses][TRANSFORM_MATRIX_DIMENSION][TRANSFORM_MATRIX_DIMENSION];
for (size_t i = 0; i < number_of_poses; ++i)
{
// Convert effector_wrt_world[i] from Eigen::isometry3d to C array
if (!toCArray(effector_wrt_world[i], c_arr_eef_wrt_world[i]))
{
*error_message = "Error converting Eigen::isometry3d to C array";
RCLCPP_ERROR_STREAM(LOGGER_CALIBRATION_SOLVER, *error_message);
Py_DECREF(python_func_add_sample);
Py_DECREF(python_instance);
PyErr_Print();
return false;
}
// From C array to PyArrayObject
python_array_eef_wrt_base[i] =
PyArray_SimpleNewFromData(number_of_dims, dims, NPY_DOUBLE, (void*)(c_arr_eef_wrt_world[i]));
if (!python_array_eef_wrt_base[i])
{
*error_message = "Error creating PyArray object";
RCLCPP_ERROR_STREAM(LOGGER_CALIBRATION_SOLVER, *error_message);
Py_DECREF(python_func_add_sample);
Py_DECREF(python_instance);
PyErr_Print();
return false;
}
numpy_arg_eef_wrt_base[i] = (PyArrayObject*)(python_array_eef_wrt_base[i]);
if (PyArray_NDIM(numpy_arg_eef_wrt_base[i]) == 2) // Check PyArrayObject dims are 4x4
{
npy_intp* py_array_dims = PyArray_DIMS(numpy_arg_eef_wrt_base[i]);
if (py_array_dims[0] != 4 || py_array_dims[1] != 4)
{
*error_message =
"Error PyArrayObject dims: " + std::to_string(py_array_dims[0]) + "x" + std::to_string(py_array_dims[1]);
RCLCPP_ERROR_STREAM(LOGGER_CALIBRATION_SOLVER, *error_message);
Py_DECREF(numpy_arg_eef_wrt_base[i]);
Py_DECREF(python_func_add_sample);
Py_DECREF(python_instance);
return false;
}
}
// Convert object_wrt_sensor[i] from Eigen::isometry3d to C array
if (!toCArray(object_wrt_sensor[i], c_arr_obj_wrt_sensor[i]))
{
*error_message = "Error converting Eigen::isometry3d to C array";
RCLCPP_ERROR_STREAM(LOGGER_CALIBRATION_SOLVER, *error_message);
Py_DECREF(python_func_add_sample);
Py_DECREF(python_instance);
PyErr_Print();
return false;
}
// From C array to PyArrayObject
python_array_obj_wrt_sensor[i] =
PyArray_SimpleNewFromData(number_of_dims, dims, NPY_DOUBLE, (void*)(c_arr_obj_wrt_sensor[i]));
if (!python_array_obj_wrt_sensor[i])
{
*error_message = "Error creating PyArray object";
RCLCPP_ERROR_STREAM(LOGGER_CALIBRATION_SOLVER, *error_message);
Py_DECREF(python_func_add_sample);
Py_DECREF(python_instance);
PyErr_Print();
return false;
}
numpy_arg_obj_wrt_sensor[i] = (PyArrayObject*)(python_array_obj_wrt_sensor[i]);
if (PyArray_NDIM(numpy_arg_obj_wrt_sensor[i]) == 2) // Check PyArrayObject dims are 4x4
{
npy_intp* py_array_dims = PyArray_DIMS(numpy_arg_obj_wrt_sensor[i]);
if (py_array_dims[0] != 4 || py_array_dims[1] != 4)
{
*error_message =
"Error PyArrayObject dims: " + std::to_string(py_array_dims[0]) + "x" + std::to_string(py_array_dims[1]);
RCLCPP_ERROR_STREAM(LOGGER_CALIBRATION_SOLVER, *error_message);
Py_DECREF(numpy_arg_obj_wrt_sensor[i]);
Py_DECREF(python_func_add_sample);
Py_DECREF(python_instance);
return false;
}
}
// Assign sample poses to 'HandEyeCalibrator' instance
python_args_sample[i] = Py_BuildValue("OO", numpy_arg_eef_wrt_base[i], numpy_arg_obj_wrt_sensor[i]);
if (!python_args_sample[i])
{
*error_message = "Can't create argument tuple for 'add_sample' method";
RCLCPP_ERROR_STREAM(LOGGER_CALIBRATION_SOLVER, *error_message);
Py_DECREF(python_func_add_sample);
Py_DECREF(python_instance);
PyErr_Print();
return false;
}
python_value = PyEval_CallObject(python_func_add_sample, python_args_sample[i]);
if (!python_value)
{
*error_message = "Error calling 'add_sample' method";
RCLCPP_ERROR_STREAM(LOGGER_CALIBRATION_SOLVER, *error_message);
Py_DECREF(python_func_add_sample);
Py_DECREF(python_instance);
PyErr_Print();
return false;
}
RCLCPP_DEBUG_STREAM(LOGGER_CALIBRATION_SOLVER, "num_samples: " << PyInt_AsLong(python_value));
Py_DECREF(python_value);
}
Py_DECREF(python_func_add_sample);
// print the pair of transforms as python arguments
for (size_t i = 0; i < number_of_poses; i++)
{
std::stringstream ss;
ss << "\nnp_arg_eef_wrt_base";
for (size_t m = 0; m < TRANSFORM_MATRIX_DIMENSION; m++)
{
ss << "\n";
for (size_t n = 0; n < TRANSFORM_MATRIX_DIMENSION; n++)
ss << *(double*)PyArray_GETPTR2(numpy_arg_eef_wrt_base[i], m, n) << " ";
}
ss << "\nnp_arg_obj_wrt_sensor";
for (size_t m = 0; m < TRANSFORM_MATRIX_DIMENSION; m++)
{
ss << "\n";
for (size_t n = 0; n < TRANSFORM_MATRIX_DIMENSION; n++)
ss << *(double*)PyArray_GETPTR2(numpy_arg_obj_wrt_sensor[i], m, n) << " ";
}
RCLCPP_DEBUG_STREAM(LOGGER_CALIBRATION_SOLVER, ss.str());
}
// Import handeye.solver python module
python_name = PyString_FromString("handeye.solver");
python_module = PyImport_Import(python_name);
Py_DECREF(python_name);
if (!python_module)
{
*error_message = "Failed to load python module: handeye.solver";
RCLCPP_ERROR_STREAM(LOGGER_CALIBRATION_SOLVER, *error_message);
Py_DECREF(python_instance);
PyErr_Print();
return false;
}
// Find handeye.solver.solver_name class
python_class = PyObject_GetAttrString(python_module, solver_name.c_str());
Py_DECREF(python_module);
if (!python_class || !PyCallable_Check(python_class))
{
*error_message = "Can't find \"" + solver_name + "\" python class";
RCLCPP_ERROR_STREAM(LOGGER_CALIBRATION_SOLVER, *error_message);
Py_DECREF(python_instance);
PyErr_Print();
return false;
}
// Find handeye.calibrator.HandEyeCalibrator.solve method
python_func_solve = PyObject_GetAttrString(python_instance, "solve");
if (!python_func_solve || !PyCallable_Check(python_func_solve))
{
*error_message = "Can't find 'solve' method";
RCLCPP_ERROR_STREAM(LOGGER_CALIBRATION_SOLVER, *error_message);
Py_DECREF(python_class);
Py_DECREF(python_instance);
PyErr_Print();
return false;
}
// Create argument list for 'solve' method
python_args = Py_BuildValue("{s:O}", "method", python_class);
Py_DECREF(python_class);
if (!python_args)
{
*error_message = "Can't create argument tuple for 'solve' method";
RCLCPP_ERROR_STREAM(LOGGER_CALIBRATION_SOLVER, *error_message);
Py_DECREF(python_instance);
PyErr_Print();
return false;
}
// Call 'solve' method to solve AX=XB problem
python_value = PyEval_CallObjectWithKeywords(python_func_solve, nullptr, python_args);
Py_DECREF(python_args);
Py_DECREF(python_func_solve);
for (size_t i = 0; i < number_of_poses; ++i)
Py_DECREF(python_args_sample[i]);
Py_DECREF(python_instance);
if (!python_value)
{
*error_message = "Error calling 'solve' method";
RCLCPP_ERROR_STREAM(LOGGER_CALIBRATION_SOLVER, *error_message);
PyErr_Print();
return false;
}
PyArrayObject* np_ret = (PyArrayObject*)python_value;
if (!PyArray_Check(python_value) || PyArray_NDIM(np_ret) != 2 || PyArray_NBYTES(np_ret) != sizeof(double) * 16)
{
*error_message = "Did not return a valid array";
RCLCPP_ERROR_STREAM(LOGGER_CALIBRATION_SOLVER, *error_message);
Py_DECREF(python_value);
PyErr_Print();
return false;
}
std::stringstream ss;
ss << "\n Result camera-robot pose";
for (size_t m = 0; m < TRANSFORM_MATRIX_DIMENSION; m++)
{
ss << "\n";
for (size_t n = 0; n < TRANSFORM_MATRIX_DIMENSION; n++)
{
double item = *(double*)PyArray_GETPTR2(np_ret, m, n);
camera_robot_pose_(m, n) = item;
ss << item << " ";
}
}
RCLCPP_DEBUG_STREAM(LOGGER_CALIBRATION_SOLVER, ss.str());
Py_DECREF(python_value);
RCLCPP_DEBUG_STREAM(LOGGER_CALIBRATION_SOLVER, "Python C API end");
return true;
}
bool HandEyeSolverDefault::toCArray(const Eigen::Isometry3d& pose, double (*c_arr)[TRANSFORM_MATRIX_DIMENSION]) const
{
const Eigen::MatrixXd& mat = pose.matrix();
if (mat.rows() != TRANSFORM_MATRIX_DIMENSION || mat.cols() != TRANSFORM_MATRIX_DIMENSION)
{
RCLCPP_ERROR(LOGGER_CALIBRATION_SOLVER, "Error matrix dims: %zux%zu, required %dx%d", mat.rows(), mat.cols(),
TRANSFORM_MATRIX_DIMENSION, TRANSFORM_MATRIX_DIMENSION);
return false;
}
for (size_t i = 0; i < TRANSFORM_MATRIX_DIMENSION; ++i)
for (size_t j = 0; j < TRANSFORM_MATRIX_DIMENSION; ++j)
c_arr[i][j] = mat(i, j);
return true;
}
} // namespace moveit_handeye_calibration