-
Notifications
You must be signed in to change notification settings - Fork 50
/
Copy pathHandEyeCalibrationCalibrate.srv
42 lines (35 loc) · 1.76 KB
/
HandEyeCalibrationCalibrate.srv
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
uint8 EYE_TO_HAND = 1
uint8 EYE_IN_HAND = 2
# The configuration to use for the hand-eye calibration: EYE_TO_HAND or EYE_IN_HAND
uint8 configuration
# Handles of hand-eye captures to use in this hand-eye calibration. Leave empty to use all captures.
int32[] capture_handles
# Optionally, add fixed objects for low degrees-of-freedom (DOF) hand-eye calibration. Leave default for regular (6-DOF)
# calibration.
FixedPlacementOfCalibrationObjects fixed_objects
---
bool success
# Textual representation of the result. Any indices being referred to correspond to entries into the provided list of
# capture handles.
#
# Note: Any reported lengths in this message are given in units of millimeter, which are used internally in the Zivid
# driver. This applies only to the textual representation of the result, other returned numerical results are given in
# the ROS convention of meter, as specified for each related field.
string message
# Computed hand-eye transform.
#
# The transform has the following meaning depending on the provided configuration:
#
# - Eye-in-hand: Camera pose in robot end-effector frame.
# - Eye-to-hand: Camera pose in robot base frame.
#
# Note: Lengths are given in units of meter. In the Zivid driver, the units are automatically converted from the default
# units of the Zivid point clouds in millimeter, to the ROS convention of meter.
geometry_msgs/Transform transform
# Hand-eye calibration residuals.
#
# Feature points (for each input pose) are transformed into a common frame. A rigid transform between feature points and
# corresponding centroids are utilized to compute residuals for rotational and translational parts.
#
# The order and size of the list of residuals correspond to the provided list of capture handles.
HandEyeCalibrationResidual[] residuals