hand_eye_calibration
— Durchführen einer Hand-Auge-Kalibrierung.
hand_eye_calibration( : : X, Y, Z, Row, Col, NumPoints, RobotPoses, CameraParam, Method, QualityType : CameraPose, CalibrationPose, Quality)
Der Operator hand_eye_calibration
bestimmt die 3D-Lage eines Roboters
(„Hand“) relativ zu einer Kamera („Auge“). Mit dieser Information können
die Ergebnisse der Bildverarbeitung in das Koordinatensystem des Roboters
transformiert werden, der dann z.B. ein inspiziertes Teil greift.
Bitte beachten Sie, dass der Operator hand_eye_calibration
keine
3D-Sensoren unterstützt. Eine Hand-Auge-Kalibrierung mit 3D-Sensoren kann
nur mit dem Operator calibrate_hand_eye
vorgenommen werden.
Jener Operator stellt des Weiteren eine benutzerfreundlichere Schnittstelle
für die Hand-Auge-Kalibrierung bereit als der hier vorliegende
Operator hand_eye_calibration
, da die jeweiligen Bezugssysteme
klar ausgezeichnet sind.
Es gibt zwei mögliche Konfigurationen von Roboter-Kamera-Systemen
(Hand-Auge-Systemen): Die Kamera kann auf dem Roboter montiert sein oder
stationär sein und den Roboter beobachten. Beachten Sie, dass der Begriff
„Roboter“ für ein beliebiges System steht, das Objekte bewegt. Daher können
mit hand_eye_calibration
viele verschiedene Systeme kalibriert
werden, von Schwenk-Neige-Köpfen zu Vielachs-Manipulatoren.
Eine Hand-Auge-Kalibrierung kann über eine geschlossene Verkettung von insgesamt vier euklidischen Transformationen beschrieben werden. In dieser Kette sind zwei nicht aufeinander folgende Transformation bekannt, welche von der Robotersteuerung und der Kalibrierung der Marker stammen. Die beiden anderen Transformation sind unbekannt aber konstant und werden durch die Hand-Auge-Kalibrierung bestimmt.
Eine Hand-Auge-Kalibrierung läuft ähnlich ab wie die Kalibrierung der
externen Kameraparameter (siehe camera_calibration
): Zuerst werden
ein Satz Bilder eines Kalibrierkörpers aufgenommen, in diesen werden dann zu
bekannten Kalibrierpunkten korrespondierende Bildpunkte gesucht und dem
Operator hand_eye_calibration
in den Parametern X
,
Y
, Z
, Row
, Col
und NumPoints
übergeben. Falls die Standard-Kalibrierplatte verwendet wird, können die
Korrespondenzen sehr einfach mit den Operatoren find_caltab
und
find_marks_and_pose
bestimmt werden. Es ist zu beachten, dass die
internen Parameter der verwendeten Kamera vorher zu kalibrieren sind.
Im Gegensatz zur Kamerakalibrierung wird der Kalibrierkörper nicht manuell
bewegt. Dies ist die Aufgabe des Roboters, der entweder die Kamera bewegt
(bei auf dem Roboter montierter Kamera) oder den Kalibrierkörper (bei
stationärer Kamera). Die Bewegungen des Roboters werden als bekannt
vorausgesetzt und daher ebenfalls als Eingabe für die Kalibrierung benutzt
(Parameter RobotPoses
).
Im Folgenden werden die zwei Hand-Auge-Konfigurationen detaillierter beschrieben, gefolgt von genereller Information über den Prozess der Hand-Auge-Kalibrierung.
In dieser Konfiguration ist der Kalibrierkörper stationär, und die Kamera wird vom Roboter an verschiedene Positionen bewegt. Die grundlegende Idee hinter der Hand-Auge-Kalibrierung ist, dass die aus einem Kalibrierbild extrahierte Information, d.h. die 3D-Lage des Kalibrierkörpers relativ zur Kamera (d.h. die externen Kameraparameter), als Kette von 3D-Lagen bzw. homogenen Transformationsmatrizen aufgefasst werden kann, vom Kalibrierkörper über die Roboter-Basis zu dessen Tool (Endeffektor) und schließlich zur Kamera:
Bewegte Kamera: cam_H_cal = cam_H_tool * tool_H_base * base_H_cal
| | |
CameraPose
RobotPoses
CalibrationPose
Aus den Kalibrierbildern bestimmt der Operator hand_eye_calibration
die zwei Transformationen an den Enden der Kette, d.h. die 3D-Lage des
Roboter-Tools in Kamerakoordinaten
(,CameraPose
)
und die 3D-Lage des Kalibrierkörpers in Roboter-Basiskoordinaten
(,CalibrationPose
).
Im Gegensatz dazu ist die Transformation in der Mitte der Kette,
, bekannt, aber unterschiedlich
für jedes Kalibrierbild, da sie die 3D-Lage des die Kamera bewegenden
Roboters beschreibt, genauer gesagt deren Inverse (3D-Lage der Roboter-Basis
in Roboter-Toolkoordinaten). Die (inversen) 3D-Lagen des Roboters in den
Kalibrierbildern müssen im Parameter RobotPoses
übergeben werden.
Es ist zu beachten, dass die Z-Translation von CalibrationPose
im Rahmen der Kalibrierung von SCARA-Robotern nicht eindeutig bestimmt
werden kann. Um diese Mehrdeutigkeit aufzulösen,
wird die Z-Translation von CalibrationPose
intern auf 0.0 gesetzt
und CameraPose
entsprechend berechnet. Es ist notwendig, die
tatsächliche Translation in Z nach der Kalibrierung zu bestimmen
(siehe calibrate_hand_eye
).
In dieser Konfiguration greift der Roboter den Kalibrierkörper und bewegt ihn vor der Kamera. Auch in dieser Konfiguration entspricht die aus einem Kalibrierbild extrahierte Information, d.h. die 3D-Lage des Kalibrierkörpers in Kamerakoordinaten (d.h. die externen Kameraparameter) einer Kette von 3D-Lagen bzw. homogenen Transformationsmatrizen, diesmal vom Kalibrierkörper über das Roboter-Tool zu dessen Basis und schließlich zur Kamera:
Stationäre Kamera: cam_H_cal = cam_H_base * base_H_tool * tool_H_cal
| | |
CameraPose
RobotPoses
CalibrationPose
Analog zur Konfiguration mit bewegter Kamera bestimmt der Operator
hand_eye_calibration
die zwei Transformationen an den Enden der
Kette, hier nun die 3D-Lage der Roboter-Basis in Kamerakoordinaten
(,CameraPose
)
und die 3D-Lage des Kalibrierkörpers in Roboter-Toolkoordinaten
(,CalibrationPose
).
Die Transformation in der Mitte der Kette,
, beschreibt die 3D-Lage des
den Kalibrierkörper bewegenden Roboters, d.h. die 3D-Lage des Roboter-Tools
in Roboter-Basiskoordinaten. Die 3D-Lagen des Roboters in den
Kalibrierbildern müssen im Parameter RobotPoses
übergeben werden.
Es ist zu beachten, dass die Z-Translation von CalibrationPose
im Rahmen der Kalibrierung von SCARA-Robotern nicht eindeutig bestimmt
werden kann. Um diese Mehrdeutigkeit aufzulösen,
wird die Z-Translation von CalibrationPose
intern auf 0.0 gesetzt
und CameraPose
entsprechend berechnet. Es ist notwendig, die
tatsächliche Translation in Z nach der Kalibrierung zu bestimmen
(siehe calibrate_hand_eye
).
Die folgenden Abschnitte befassen sich jeweils mit einzelnen Fragen,
die sich bei der Verwendung von hand_eye_calibration
stellen
und sollen daher sowohl dem Verständnis als auch als Leitfaden
für die eigene Anwendung dienen.
Als Grundlage für die Hand-Auge-Kalibrierung dienen 3D-Kalibrierpunkte im
Weltkoordinatensystem (X
, Y
, Y
) und ihre
zugehörigen Abbildungen im Bildkoordinatensystem (Row
,
Col
). Für eine erfolgreiche Hand-Auge-Kalibrierung müssen möglichst
viele Bilder der 3D-Kalibrierpunkte aus möglichst unterschiedlichen
Roboterpositionen aufgenommen werden.
Prinzipiell können beliebige bekannte Punkte im Weltkoordinatensystem
verwendet werden. Man muss lediglich die Projektionen im Bild
kennen. Idealerweise verwendet man jedoch eine Standard-Kalibrierplatte, wie
sie mit gen_caltab
erzeugt werden kann. Dann können mit
find_caltab
und find_marks_and_pose
die Positionen der
Kalibrierplatte und ihrer Marken extrahiert werden; der Operator
caltab_points
liefert die 3D-Koordinaten der Kalibriermarken (siehe
auch die Beschreibung von camera_calibration
).
Mit dem Parameter NumPoints
wird angegeben, wie viele
3D-Kalibrierpunkte für jede Lage des Roboters und damit für jedes
Kalibrierbild verwendet werden. Damit ist die Zuordnung der in X
,
Y
, Y
linearisiert angegebenen 3D-Kalibrierpunkte und ihrer
Projektionen (Row
, Col
) zu der entsprechenden 3D-Lage des
Roboters (RobotPoses
) möglich. Beachten Sie, dass im Gegensatz zu
camera_calibration
die 3D-Koordinaten der Kalibrierpunkte für jedes
Kalibrierbild angegeben werden müssen und nicht nur einmal!
Ist eine Standard-Kalibrierplatte vorhanden, sollte folgendermaßen vorgegangen werden:
Die Position des Kalibrierkörpers (bewegte Kamera: relativ zur Roboter-Basis; stationäre Kamera: relativ zum Roboter-Tool) und die Position der Kamera (bewegte Kamera: relativ zum Roboter-Tool; stationäre Kamera: relativ zur Roboter-Basis) bleiben während der Aufnahmen unverändert.
Die internen Kameraparameter sind konstant und müssen zuvor bestimmt sein
und in CameraParam
übergeben werden (vgl.
camera_calibration
). Beachten Sie, dass Veränderungen der
Bildgröße, der Brennweite, der Blende oder des Fokus eine Veränderung
der internen Kameraparameter bedeuten.
Die theoretisch minimale Anzahl der aufzunehmenden Bilder ist drei. Aber, es wird empfohlen mindestens 10 Bilder aufzunehmen, bei denen die Position der Kamera bzw. die Position der Roboterhand möglichst stark variiert.
Für konventionelle (d.h. nicht-SCARA) Roboter ist ein ausreichendes Ausmaß an Rotation zwischen den Bildern notwendig und sollte mindestens 30 Grad besser aber 60 Grad betragen. Die Rotationen zwischen den Posen des Kalibrierobjektes müssen mindestens zwei verschiedene Rotationsachsen aufweisen. Sehr verschiedene Orientierungen führen zu präziseren Ergebnissen in der Hand-Auge-Kalibrierung. SCARA-Roboter weisen nur eine Rotationsachse auf. Die Rotation zwischen den Bildern sollte ebenfalls groß sein.
Die Kalibrierplatte muss jeweils komplett (inkl. Rand!) im Bild sichtbar sein.
Es sollten möglichst keine Reflexionen oder ähnliche Störungen auf der Kalibrierplatte zu sehen sein.
Werden individuelle Marker anstelle der Kalibrierplatte verwendet, so ist die minimale Anzahl der Marker in jedem Bild vier.
Die Kalibrierplatte sollte jeweils mindestens etwa ein Viertel des gesamten Bildes ausfüllen, damit die Marken robust detektiert werden können.
Die Kamera darf zwischen den Aufnahmen nicht verändert werden, d.h. weder Brennweite und Blende, noch Fokussierung darf verändert werden, denn für alle Aufnahmen gelten die gleichen internen Kameraparameter. Achten Sie darauf, dass bei einer Änderung des Abstands der Kamera vom Kalibrierkörper durch die Roboterbewegung die Fokussierung (Schärfe im Bild) noch ausreicht. Sorgen Sie daher bei den Aufnahmen für eine gute Ausleuchtung der Kalibrierplatte, denn die Tiefenschärfe nimmt mit kleiner Blende zu.
Im Parameter RobotPoses
müssen die 3D-Lagen des Roboters in den
Kalibrierbildern (bewegte Kamera: 3D-Lage der Roboter-Basis in
Roboter-Toolkoordinaten; stationäre Kamera: 3D-Lage des Roboter-Tools in
Roboter-Basiskoordinaten) übergeben werden. Wir empfehlen, die 3D-Lagen in
einem separaten Programm zu erzeugen und mittels write_pose
in
Dateien abzuspeichern. Im Kalibrierprogramm können sie dann eingelesen
und in einem Tupel aufgesammelt werden, wie das Beispiel weiter unten
zeigt. Außerdem empfehlen wir, in den Dateien unabhängig von der
verwendeten Hand-Auge-Koordination die 3D-Lage des Roboter-Tools in
Roboter-Basiskoordinaten zu speichern. Beim Einsatz einer bewegten Kamera
erfolgt die Invertierung der eingelesenen 3D-Lagen dann vor dem Einfügen in
das Tupel. Auch dies ist im Beispielprogramm beschrieben.
Die 3D-Lage eines Roboters kann über seine kartesische Schnittstelle
typischerweise in einer Notation abgefragt werden, die den Darstellungstypen
mit den Codes 0 oder 2 entsprechen (OrderOfRotation
=
'gba' oder 'abg' , siehe create_pose
). In diesem
Fall können die abgefragten Werte direkt als Eingabe für create_pose
verwendet werden.
Falls die kartesische Schnittstelle des Roboters die Orientierung anders
beschreibt, z.B. in der Darstellung ZYZ (), kann die entsprechende homogene
Transformationsmatrix schrittweise mit den Operatoren
hom_mat3d_rotate
und hom_mat3d_translate
aufgebaut und dann
mit hom_mat3d_to_pose
in eine 3D-Lage gewandelt werden. Der folgende
Beispiel-Code erzeugt eine 3D-Lage aus der oben beschriebenen
ZYZ-Darstellung:
hom_mat3d_identity (HomMat3DIdent) hom_mat3d_rotate (HomMat3DIdent, phi3, 'z', 0, 0, 0, HomMat3DRotZ) hom_mat3d_rotate (HomMat3DRotZ, phi2, 'y', 0, 0, 0, HomMat3DRotZY) hom_mat3d_rotate (HomMat3DRotZY, phi1, 'z', 0, 0, 0, HomMat3DRotZYZ) hom_mat3d_translate (HomMat3DRotZYZ, Tx, Ty, Tz, base_H_tool) hom_mat3d_to_pose (base_H_tool, RobPose)
Bitte beachten Sie, dass die Hand-Auge-Kalibrierung nur dann erfolgreich sein
kann, wenn die Roboterpositionen RobotPoses
mit hoher Genauigkeit
angegeben werden!
Die Länge des Tupels NumPoints
entspricht der Anzahl der
verschiedenen Positionen des Roboters und damit der Anzahl der
Kalibrierbilder. Mit NumPoints
wird angegeben, wie viele
Kalibrierpunkte pro Bild verwendet werden. Wird die Standard-Kalibrierplatte
verwendet, so sind dies 49 Punkte pro Bild. Wurden 15 Aufnahmen gemacht
so ist NumPoints
ein Tupel der Länge 15, wobei alle Einträge
die Zahl 49 enthalten.
Die Anzahl der Kalibrierbilder muss auch bei den Tupeln mit den Koordinaten
der 3D-Kalibriermarkenpunkte bzw. der extrahierten 2D-Markenpunkte
berücksichtigt werden. Bei einer Anzahl von 15 Kalibriwerbildern mit jeweils
49 Markenpunkte müssen daher die Tupel Row
, Col
,
X
, Y
und Z
Werte enthalten. Die Reihenfolge der Werte erfolgt dabei bildweise. d.h.
die ersten 49 Werte gehören zu den 49 Marken im ersten Bild. Die Reihenfolge
der 3D-Markenpunkte und der 2D-Markenpunkte muss in jedem Bild gleich sein.
Die Länge des Tupels RobotPoses
ist ebenfalls abhängig von der
Anzahl der Kalibrierbilder. Werden beispielsweise 15 Aufnahmen und damit
15 3D-Lagen verwendet, so ergibt sich die Länge des Tupels
RobotPoses
zu 15*7=105 (15 mal je 7 Lageparameter). Die ersten 7
Werte entsprechen daher der 3D-Lage des Roboters bei der ersten Aufnahme,
die nächsten 7 denen bei der zweiten Aufnahme usw.
Der Parameter Method
bestimmt den zugrunde liegenden Algorithmus
der Hand-Auge-Kalibrierung: Mit 'linear' wird ein linearer
Algorithmus ausgewählt, welcher schnell aber in praktischen Fällen nicht
besonders genau ist. Mit 'nonlinear' wird ein nicht linearer
Algorithmus gewählt, welcher das genaueste Ergebnis liefert und daher auch
empfohlen ist.
Für die Kalibrierung von SCARA-Robotern muss für Method
'scara_linear' oder 'scara_nonlinear' gewählt werden.
Während der Arm eines anthropomorphen Roboters 3 Drehgelenke hat, die
typischerweise 6 Freiheitsgrade abdecken (3 Translationen und 3
Rotationen) besitzen SCARA-Roboter dagegen nur zwei parallele
Drehgelenke und ein paralleles Schubgelenk, die nur 4 Freiheitsgrade
(3 Translationen und 1 Rotation) abdecken. Grob gesagt ist ein
anthropomorpher Roboter im Gegensatz zum SCARA-Roboter in der Lage,
seinen Endeffektor zu verkippen.
Der Parameter QualityType
schaltet zwischen unterschiedlichen
Möglichkeiten die Qualität der Ergebnisse im Ausgabewert Quality
zu beurteilen. Mit 'error_pose' wird der Lagefehler über die
komplette Transformationskette gewählt. Genaugenommen wird ein Tuple mit vier
Elementen zurückgegeben, welches zuerst den mittleren, quadratischen Fehler
der Translation, dann den mittleren, quadratischen Fehler der Rotation, an
dritter Stelle den maximalen Fehler der Translation und schließlich an
vierter Stelle den maximalen Fehler der Rotation angibt.
Mit 'standard_deviation' wird ein 12-elementiges Tuple mit den
Standardabweichungen der beiden berechneten Lagen ausgegeben: Die ersten
sechs Elemente beziehen sich auf die Kameralage und die zweiten sechs auf die
Lage der Kalibriermarker.
Bei der Wahl von 'covariance' wird die volle 12x12 Kovarianzmatrix
beider Lagen zurückgegeben. Wie die Poseparameter selbst, werden auch die
Standardabweichungen und die Kovarianzen in den Einheiten [m] und [°]
angegeben.
Es ist zu beachten, dass bei der Wahl von 'linear' oder
'scara_linear' als Parameter
Method
nur die Qualitätsbewertung für den Lagefehler
('error_pose' ) möglich ist.
X
(input_control) number-array →
(real / integer)
Linearisierte Liste, die alle x-Koordinaten der Kalibrierpunkte enthält (in der Bildreihenfolge).
Y
(input_control) number-array →
(real / integer)
Linearisierte Liste, die alle y-Koordinaten der Kalibrierpunkte enthält (in der Bildreihenfolge).
Z
(input_control) number-array →
(real / integer)
Linearisierte Liste, die alle z-Koordinaten der Kalibrierpunkte enthält (in der Bildreihenfolge).
Row
(input_control) number-array →
(real / integer)
Linearisierte Liste, die alle Zeilenkoordinaten der Kalibrierpunkte enthält (in der Bildreihenfolge).
Col
(input_control) number-array →
(real / integer)
Linearisierte Liste, die alle Spaltenkoordinaten der Kalibrierpunkte enthält (in der Bildreihenfolge).
NumPoints
(input_control) integer-array →
(integer)
Für jedes Bild: Anzahl der Kalibrierpunkte.
RobotPoses
(input_control) pose-array →
(real / integer)
Zu jedem Bild die bekannten Werte für die 3D-Lage des Roboters (bewegte Kamera: Roboter-Basis in Roboter-Toolkoordinaten; stationäre Kamera: Roboter-Tool in Roboter-Basiskoordinaten).
CameraParam
(input_control) campar →
(real / integer / string)
Interne Kameraparameter.
Method
(input_control) string →
(string)
Methode der Hand-Auge-Kalibrierung.
Defaultwert: 'nonlinear'
Werteliste: 'linear' , 'nonlinear' , 'scara_linear' , 'scara_nonlinear'
QualityType
(input_control) string(-array) →
(string)
Typ der Qualitätsbewertung.
Defaultwert: 'error_pose'
Werteliste: 'covariance' , 'error_pose' , 'standard_deviation'
CameraPose
(output_control) pose →
(real / integer)
Berechnete relative Kamera Lage: 3D-Lage des Roboter-Tools (bewegte Kamera) bzw. der Roboter-Basis (stationäre Kamera) in Kamerakoordinaten.
CalibrationPose
(output_control) pose →
(real / integer)
Berechnete 3D-Lage der Kalibriermarker in Roboter-Basiskoordinaten (bewegte Kamera) bzw. Roboter-Toolkoordinaten (stationäre Kamera).
Quality
(output_control) real(-array) →
(real)
Qualitätsbewertung des Ergebnisses.
* Note that, in order to use this code snippet, you must provide * the camera parameters, the calibration plate description file, * the calibration images, and the robot poses. read_cam_par('campar.dat', CameraParam) CalDescr := 'caltab.descr' caltab_points(CalDescr, X, Y, Z) * Process all calibration images. for i := 0 to NumImages-1 by 1 read_image(Image, 'calib_'+i$'02d') * Find marks on the calibration plate in every image. find_caltab(Image, CalPlate, CalDescr, 3, 150, 5) find_marks_and_pose(Image, CalPlate, CalDescr, CameraParam, 128, 10, 18, \ 0.9, 15, 100, RCoordTmp, CCoordTmp, StartPose) * Accumulate 2D and 3D coordinates of the marks. RCoord := [RCoord, RCoordTmp] CCoord := [CCoord, CCoordTmp] XCoord := [XCoord, X] YCoord := [YCoord, Y] ZCoord := [ZCoord, Z] NumMarker := [NumMarker, |RCoordTmp|] * Read pose of the robot tool in robot base coordinates. read_pose('robpose_'+i$'02d'+'.dat', RobPose) * Moving camera? Invert pose. if (IsMovingCameraConfig == 'true') pose_to_hom_mat3d(RobPose, base_H_tool) hom_mat3d_invert(base_H_tool, tool_H_base) hom_mat3d_to_pose(tool_H_base, RobPose) endif * Accumulate robot poses. RobotPoses := [RobotPoses, RobPose] endfor * * Perform hand-eye calibration. * hand_eye_calibration(XCoord, YCoord, ZCoord, RCoord, CCoord, NumMarker, \ RobotPoses, CameraParam, 'nonlinear', 'error_pose', \ CameraPose, CalibrationPose, Error)
hand_eye_calibration
liefert den Wert H_MSG_2 (H_MSG_TRUE), falls die
übergebenen Parameter korrekt sind.
Ansonsten wird eine Fehlerbehandlung durchgeführt.
find_marks_and_pose
,
camera_calibration
,
calibrate_cameras
write_pose
,
convert_pose_type
,
pose_to_hom_mat3d
,
disp_caltab
,
sim_caltab
find_caltab
,
find_marks_and_pose
,
disp_caltab
,
sim_caltab
,
write_cam_par
,
read_cam_par
,
create_pose
,
convert_pose_type
,
write_pose
,
read_pose
,
pose_to_hom_mat3d
,
hom_mat3d_to_pose
,
caltab_points
,
gen_caltab
,
calibrate_hand_eye
K. Daniilidis: „Hand-Eye Calibration Using Dual Quaternions“;
International Journal of Robotics Research, Vol. 18, No. 3,
pp. 286-298; 1999.
M. Ulrich, C. Steger: „Hand-Eye Calibration of SCARA Robots Using Dual
Quaternions“; Pattern Recognition and Image Analysis, Vol. 26, No. 1,
pp. 231-239; January 2016.
Calibration