hand_eye_calibrationT_hand_eye_calibrationHandEyeCalibrationHandEyeCalibration (Operator)

Name

hand_eye_calibrationT_hand_eye_calibrationHandEyeCalibrationHandEyeCalibration — Durchführen einer Hand-Auge-Kalibrierung.

Signatur

hand_eye_calibration( : : X, Y, Z, Row, Col, NumPoints, RobotPoses, CameraParam, Method, QualityType : CameraPose, CalibrationPose, Quality)

Herror T_hand_eye_calibration(const Htuple X, const Htuple Y, const Htuple Z, const Htuple Row, const Htuple Col, const Htuple NumPoints, const Htuple RobotPoses, const Htuple CameraParam, const Htuple Method, const Htuple QualityType, Htuple* CameraPose, Htuple* CalibrationPose, Htuple* Quality)

void HandEyeCalibration(const HTuple& X, const HTuple& Y, const HTuple& Z, const HTuple& Row, const HTuple& Col, const HTuple& NumPoints, const HTuple& RobotPoses, const HTuple& CameraParam, const HTuple& Method, const HTuple& QualityType, HTuple* CameraPose, HTuple* CalibrationPose, HTuple* Quality)

HPose HCamPar::HandEyeCalibration(const HTuple& X, const HTuple& Y, const HTuple& Z, const HTuple& Row, const HTuple& Col, const HTuple& NumPoints, const HPoseArray& RobotPoses, const HString& Method, const HTuple& QualityType, HPose* CalibrationPose, HTuple* Quality) const

HPose HCamPar::HandEyeCalibration(const HTuple& X, const HTuple& Y, const HTuple& Z, const HTuple& Row, const HTuple& Col, const HTuple& NumPoints, const HPoseArray& RobotPoses, const HString& Method, const HString& QualityType, HPose* CalibrationPose, double* Quality) const

HPose HCamPar::HandEyeCalibration(const HTuple& X, const HTuple& Y, const HTuple& Z, const HTuple& Row, const HTuple& Col, const HTuple& NumPoints, const HPoseArray& RobotPoses, const char* Method, const char* QualityType, HPose* CalibrationPose, double* Quality) const

HPose HCamPar::HandEyeCalibration(const HTuple& X, const HTuple& Y, const HTuple& Z, const HTuple& Row, const HTuple& Col, const HTuple& NumPoints, const HPoseArray& RobotPoses, const wchar_t* Method, const wchar_t* QualityType, HPose* CalibrationPose, double* Quality) const   (Nur Windows)

static HPose HPose::HandEyeCalibration(const HTuple& X, const HTuple& Y, const HTuple& Z, const HTuple& Row, const HTuple& Col, const HTuple& NumPoints, const HPoseArray& RobotPoses, const HCamPar& CameraParam, const HString& Method, const HTuple& QualityType, HPose* CalibrationPose, HTuple* Quality)

static HPose HPose::HandEyeCalibration(const HTuple& X, const HTuple& Y, const HTuple& Z, const HTuple& Row, const HTuple& Col, const HTuple& NumPoints, const HPoseArray& RobotPoses, const HCamPar& CameraParam, const HString& Method, const HString& QualityType, HPose* CalibrationPose, double* Quality)

static HPose HPose::HandEyeCalibration(const HTuple& X, const HTuple& Y, const HTuple& Z, const HTuple& Row, const HTuple& Col, const HTuple& NumPoints, const HPoseArray& RobotPoses, const HCamPar& CameraParam, const char* Method, const char* QualityType, HPose* CalibrationPose, double* Quality)

static HPose HPose::HandEyeCalibration(const HTuple& X, const HTuple& Y, const HTuple& Z, const HTuple& Row, const HTuple& Col, const HTuple& NumPoints, const HPoseArray& RobotPoses, const HCamPar& CameraParam, const wchar_t* Method, const wchar_t* QualityType, HPose* CalibrationPose, double* Quality)   (Nur Windows)

static void HOperatorSet.HandEyeCalibration(HTuple x, HTuple y, HTuple z, HTuple row, HTuple col, HTuple numPoints, HTuple robotPoses, HTuple cameraParam, HTuple method, HTuple qualityType, out HTuple cameraPose, out HTuple calibrationPose, out HTuple quality)

HPose HCamPar.HandEyeCalibration(HTuple x, HTuple y, HTuple z, HTuple row, HTuple col, HTuple numPoints, HPose[] robotPoses, string method, HTuple qualityType, out HPose calibrationPose, out HTuple quality)

HPose HCamPar.HandEyeCalibration(HTuple x, HTuple y, HTuple z, HTuple row, HTuple col, HTuple numPoints, HPose[] robotPoses, string method, string qualityType, out HPose calibrationPose, out double quality)

static HPose HPose.HandEyeCalibration(HTuple x, HTuple y, HTuple z, HTuple row, HTuple col, HTuple numPoints, HPose[] robotPoses, HCamPar cameraParam, string method, HTuple qualityType, out HPose calibrationPose, out HTuple quality)

static HPose HPose.HandEyeCalibration(HTuple x, HTuple y, HTuple z, HTuple row, HTuple col, HTuple numPoints, HPose[] robotPoses, HCamPar cameraParam, string method, string qualityType, out HPose calibrationPose, out double quality)

Beschreibung

Der Operator hand_eye_calibrationhand_eye_calibrationHandEyeCalibrationHandEyeCalibrationHandEyeCalibration 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_calibrationhand_eye_calibrationHandEyeCalibrationHandEyeCalibrationHandEyeCalibration keine 3D-Sensoren unterstützt. Eine Hand-Auge-Kalibrierung mit 3D-Sensoren kann nur mit dem Operator calibrate_hand_eyecalibrate_hand_eyeCalibrateHandEyeCalibrateHandEyeCalibrateHandEye vorgenommen werden. Jener Operator stellt des Weiteren eine benutzerfreundlichere Schnittstelle für die Hand-Auge-Kalibrierung bereit als der hier vorliegende Operator hand_eye_calibrationhand_eye_calibrationHandEyeCalibrationHandEyeCalibrationHandEyeCalibration, 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_calibrationhand_eye_calibrationHandEyeCalibrationHandEyeCalibrationHandEyeCalibration 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_calibrationcamera_calibrationCameraCalibrationCameraCalibrationCameraCalibration): Zuerst werden ein Satz Bilder eines Kalibrierkörpers aufgenommen, in diesen werden dann zu bekannten Kalibrierpunkten korrespondierende Bildpunkte gesucht und dem Operator hand_eye_calibrationhand_eye_calibrationHandEyeCalibrationHandEyeCalibrationHandEyeCalibration in den Parametern XXXXx, YYYYy, ZZZZz, RowRowRowRowrow, ColColColColcol und NumPointsNumPointsNumPointsNumPointsnumPoints übergeben. Falls die Standard-Kalibrierplatte verwendet wird, können die Korrespondenzen sehr einfach mit den Operatoren find_caltabfind_caltabFindCaltabFindCaltabFindCaltab und find_marks_and_posefind_marks_and_poseFindMarksAndPoseFindMarksAndPoseFindMarksAndPose 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 RobotPosesRobotPosesRobotPosesRobotPosesrobotPoses).

Im Folgenden werden die zwei Hand-Auge-Konfigurationen detaillierter beschrieben, gefolgt von genereller Information über den Prozess der Hand-Auge-Kalibrierung.

Bewegte Kamera (auf dem Roboter montiert)

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 | | | CameraPoseCameraPoseCameraPoseCameraPosecameraPose RobotPosesRobotPosesRobotPosesRobotPosesrobotPoses CalibrationPoseCalibrationPoseCalibrationPoseCalibrationPosecalibrationPose

Aus den Kalibrierbildern bestimmt der Operator hand_eye_calibrationhand_eye_calibrationHandEyeCalibrationHandEyeCalibrationHandEyeCalibration die zwei Transformationen an den Enden der Kette, d.h. die 3D-Lage des Roboter-Tools in Kamerakoordinaten ( ,CameraPoseCameraPoseCameraPoseCameraPosecameraPose) und die 3D-Lage des Kalibrierkörpers in Roboter-Basiskoordinaten ( ,CalibrationPoseCalibrationPoseCalibrationPoseCalibrationPosecalibrationPose).

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 RobotPosesRobotPosesRobotPosesRobotPosesrobotPoses übergeben werden.

Es ist zu beachten, dass die Z-Translation von CalibrationPoseCalibrationPoseCalibrationPoseCalibrationPosecalibrationPose im Rahmen der Kalibrierung von SCARA-Robotern nicht eindeutig bestimmt werden kann. Um diese Mehrdeutigkeit aufzulösen, wird die Z-Translation von CalibrationPoseCalibrationPoseCalibrationPoseCalibrationPosecalibrationPose intern auf 0.0 gesetzt und CameraPoseCameraPoseCameraPoseCameraPosecameraPose entsprechend berechnet. Es ist notwendig, die tatsächliche Translation in Z nach der Kalibrierung zu bestimmen (siehe calibrate_hand_eyecalibrate_hand_eyeCalibrateHandEyeCalibrateHandEyeCalibrateHandEye).

Stationäre Kamera

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 | | | CameraPoseCameraPoseCameraPoseCameraPosecameraPose RobotPosesRobotPosesRobotPosesRobotPosesrobotPoses CalibrationPoseCalibrationPoseCalibrationPoseCalibrationPosecalibrationPose

Analog zur Konfiguration mit bewegter Kamera bestimmt der Operator hand_eye_calibrationhand_eye_calibrationHandEyeCalibrationHandEyeCalibrationHandEyeCalibration die zwei Transformationen an den Enden der Kette, hier nun die 3D-Lage der Roboter-Basis in Kamerakoordinaten ( ,CameraPoseCameraPoseCameraPoseCameraPosecameraPose) und die 3D-Lage des Kalibrierkörpers in Roboter-Toolkoordinaten ( ,CalibrationPoseCalibrationPoseCalibrationPoseCalibrationPosecalibrationPose).

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 RobotPosesRobotPosesRobotPosesRobotPosesrobotPoses übergeben werden.

Es ist zu beachten, dass die Z-Translation von CalibrationPoseCalibrationPoseCalibrationPoseCalibrationPosecalibrationPose im Rahmen der Kalibrierung von SCARA-Robotern nicht eindeutig bestimmt werden kann. Um diese Mehrdeutigkeit aufzulösen, wird die Z-Translation von CalibrationPoseCalibrationPoseCalibrationPoseCalibrationPosecalibrationPose intern auf 0.0 gesetzt und CameraPoseCameraPoseCameraPoseCameraPosecameraPose entsprechend berechnet. Es ist notwendig, die tatsächliche Translation in Z nach der Kalibrierung zu bestimmen (siehe calibrate_hand_eyecalibrate_hand_eyeCalibrateHandEyeCalibrateHandEyeCalibrateHandEye).

Zusätzliche Information über den Kalibrierprozess

Die folgenden Abschnitte befassen sich jeweils mit einzelnen Fragen, die sich bei der Verwendung von hand_eye_calibrationhand_eye_calibrationHandEyeCalibrationHandEyeCalibrationHandEyeCalibration stellen und sollen daher sowohl dem Verständnis als auch als Leitfaden für die eigene Anwendung dienen.

Wie erhalte ich die 3D-Kalibrierpunkte?

Als Grundlage für die Hand-Auge-Kalibrierung dienen 3D-Kalibrierpunkte im Weltkoordinatensystem (XXXXx, YYYYy, YYYYy) und ihre zugehörigen Abbildungen im Bildkoordinatensystem (RowRowRowRowrow, ColColColColcol). 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_caltabgen_caltabGenCaltabGenCaltabGenCaltab erzeugt werden kann. Dann können mit find_caltabfind_caltabFindCaltabFindCaltabFindCaltab und find_marks_and_posefind_marks_and_poseFindMarksAndPoseFindMarksAndPoseFindMarksAndPose die Positionen der Kalibrierplatte und ihrer Marken extrahiert werden; der Operator caltab_pointscaltab_pointsCaltabPointsCaltabPointsCaltabPoints liefert die 3D-Koordinaten der Kalibriermarken (siehe auch die Beschreibung von camera_calibrationcamera_calibrationCameraCalibrationCameraCalibrationCameraCalibration).

Mit dem Parameter NumPointsNumPointsNumPointsNumPointsnumPoints 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 XXXXx, YYYYy, YYYYy linearisiert angegebenen 3D-Kalibrierpunkte und ihrer Projektionen (RowRowRowRowrow, ColColColColcol) zu der entsprechenden 3D-Lage des Roboters (RobotPosesRobotPosesRobotPosesRobotPosesrobotPoses) möglich. Beachten Sie, dass im Gegensatz zu camera_calibrationcamera_calibrationCameraCalibrationCameraCalibrationCameraCalibration die 3D-Koordinaten der Kalibrierpunkte für jedes Kalibrierbild angegeben werden müssen und nicht nur einmal!

Wie nehme ich eine Menge von geeigneten Bildern auf?

Ist eine Standard-Kalibrierplatte vorhanden, sollte folgendermaßen vorgegangen werden:

Wie erhalte ich die Lagen der Bewegungseinheit?

Im Parameter RobotPosesRobotPosesRobotPosesRobotPosesrobotPoses 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_posewrite_poseWritePoseWritePoseWritePose 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 (OrderOfRotationOrderOfRotationOrderOfRotationOrderOfRotationorderOfRotation = 'gba'"gba""gba""gba""gba" oder 'abg'"abg""abg""abg""abg", siehe create_posecreate_poseCreatePoseCreatePoseCreatePose). In diesem Fall können die abgefragten Werte direkt als Eingabe für create_posecreate_poseCreatePoseCreatePoseCreatePose 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_rotatehom_mat3d_rotateHomMat3dRotateHomMat3dRotateHomMat3dRotate und hom_mat3d_translatehom_mat3d_translateHomMat3dTranslateHomMat3dTranslateHomMat3dTranslate aufgebaut und dann mit hom_mat3d_to_posehom_mat3d_to_poseHomMat3dToPoseHomMat3dToPoseHomMat3dToPose 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 RobotPosesRobotPosesRobotPosesRobotPosesrobotPoses mit hoher Genauigkeit angegeben werden!

Wie sieht die Reihenfolge der einzelnen Parameter aus?

Die Länge des Tupels NumPointsNumPointsNumPointsNumPointsnumPoints entspricht der Anzahl der verschiedenen Positionen des Roboters und damit der Anzahl der Kalibrierbilder. Mit NumPointsNumPointsNumPointsNumPointsnumPoints 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 NumPointsNumPointsNumPointsNumPointsnumPoints 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 RowRowRowRowrow, ColColColColcol, XXXXx, YYYYy und ZZZZz 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 RobotPosesRobotPosesRobotPosesRobotPosesrobotPoses 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 RobotPosesRobotPosesRobotPosesRobotPosesrobotPoses 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.

Algorithmen und Ausgabeparameter

Der Parameter MethodMethodMethodMethodmethod bestimmt den zugrunde liegenden Algorithmus der Hand-Auge-Kalibrierung: Mit 'linear'"linear""linear""linear""linear" wird ein linearer Algorithmus ausgewählt, welcher schnell aber in praktischen Fällen nicht besonders genau ist. Mit 'nonlinear'"nonlinear""nonlinear""nonlinear""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 MethodMethodMethodMethodmethod 'scara_linear'"scara_linear""scara_linear""scara_linear""scara_linear" oder 'scara_nonlinear'"scara_nonlinear""scara_nonlinear""scara_nonlinear""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 QualityTypeQualityTypeQualityTypeQualityTypequalityType schaltet zwischen unterschiedlichen Möglichkeiten die Qualität der Ergebnisse im Ausgabewert QualityQualityQualityQualityquality zu beurteilen. Mit 'error_pose'"error_pose""error_pose""error_pose""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'"standard_deviation""standard_deviation""standard_deviation""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'"covariance""covariance""covariance""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'"linear""linear""linear""linear" oder 'scara_linear'"scara_linear""scara_linear""scara_linear""scara_linear" als Parameter MethodMethodMethodMethodmethod nur die Qualitätsbewertung für den Lagefehler ('error_pose'"error_pose""error_pose""error_pose""error_pose") möglich ist.

Ausführungsinformationen

Parameter

XXXXx (input_control)  number-array HTupleHTupleHtuple (real / integer) (double / int / long) (double / Hlong) (double / Hlong)

Linearisierte Liste, die alle x-Koordinaten der Kalibrierpunkte enthält (in der Bildreihenfolge).

YYYYy (input_control)  number-array HTupleHTupleHtuple (real / integer) (double / int / long) (double / Hlong) (double / Hlong)

Linearisierte Liste, die alle y-Koordinaten der Kalibrierpunkte enthält (in der Bildreihenfolge).

ZZZZz (input_control)  number-array HTupleHTupleHtuple (real / integer) (double / int / long) (double / Hlong) (double / Hlong)

Linearisierte Liste, die alle z-Koordinaten der Kalibrierpunkte enthält (in der Bildreihenfolge).

RowRowRowRowrow (input_control)  number-array HTupleHTupleHtuple (real / integer) (double / int / long) (double / Hlong) (double / Hlong)

Linearisierte Liste, die alle Zeilenkoordinaten der Kalibrierpunkte enthält (in der Bildreihenfolge).

ColColColColcol (input_control)  number-array HTupleHTupleHtuple (real / integer) (double / int / long) (double / Hlong) (double / Hlong)

Linearisierte Liste, die alle Spaltenkoordinaten der Kalibrierpunkte enthält (in der Bildreihenfolge).

NumPointsNumPointsNumPointsNumPointsnumPoints (input_control)  integer-array HTupleHTupleHtuple (integer) (int / long) (Hlong) (Hlong)

Für jedes Bild: Anzahl der Kalibrierpunkte.

RobotPosesRobotPosesRobotPosesRobotPosesrobotPoses (input_control)  pose-array HPose, HTupleHTupleHtuple (real / integer) (double / int / long) (double / Hlong) (double / Hlong)

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).

CameraParamCameraParamCameraParamCameraParamcameraParam (input_control)  campar HCamPar, HTupleHTupleHtuple (real / integer / string) (double / int / long / string) (double / Hlong / HString) (double / Hlong / char*)

Interne Kameraparameter.

MethodMethodMethodMethodmethod (input_control)  string HTupleHTupleHtuple (string) (string) (HString) (char*)

Methode der Hand-Auge-Kalibrierung.

Defaultwert: 'nonlinear' "nonlinear" "nonlinear" "nonlinear" "nonlinear"

Werteliste: 'linear'"linear""linear""linear""linear", 'nonlinear'"nonlinear""nonlinear""nonlinear""nonlinear", 'scara_linear'"scara_linear""scara_linear""scara_linear""scara_linear", 'scara_nonlinear'"scara_nonlinear""scara_nonlinear""scara_nonlinear""scara_nonlinear"

QualityTypeQualityTypeQualityTypeQualityTypequalityType (input_control)  string(-array) HTupleHTupleHtuple (string) (string) (HString) (char*)

Typ der Qualitätsbewertung.

Defaultwert: 'error_pose' "error_pose" "error_pose" "error_pose" "error_pose"

Werteliste: 'covariance'"covariance""covariance""covariance""covariance", 'error_pose'"error_pose""error_pose""error_pose""error_pose", 'standard_deviation'"standard_deviation""standard_deviation""standard_deviation""standard_deviation"

CameraPoseCameraPoseCameraPoseCameraPosecameraPose (output_control)  pose HPose, HTupleHTupleHtuple (real / integer) (double / int / long) (double / Hlong) (double / Hlong)

Berechnete relative Kamera Lage: 3D-Lage des Roboter-Tools (bewegte Kamera) bzw. der Roboter-Basis (stationäre Kamera) in Kamerakoordinaten.

CalibrationPoseCalibrationPoseCalibrationPoseCalibrationPosecalibrationPose (output_control)  pose HPose, HTupleHTupleHtuple (real / integer) (double / int / long) (double / Hlong) (double / Hlong)

Berechnete 3D-Lage der Kalibriermarker in Roboter-Basiskoordinaten (bewegte Kamera) bzw. Roboter-Toolkoordinaten (stationäre Kamera).

QualityQualityQualityQualityquality (output_control)  real(-array) HTupleHTupleHtuple (real) (double) (double) (double)

Qualitätsbewertung des Ergebnisses.

Beispiel (HDevelop)

* 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)

Ergebnis

hand_eye_calibrationhand_eye_calibrationHandEyeCalibrationHandEyeCalibrationHandEyeCalibration liefert den Wert H_MSG_2 (H_MSG_TRUE), falls die übergebenen Parameter korrekt sind. Ansonsten wird eine Fehlerbehandlung durchgeführt.

Vorgänger

find_marks_and_posefind_marks_and_poseFindMarksAndPoseFindMarksAndPoseFindMarksAndPose, camera_calibrationcamera_calibrationCameraCalibrationCameraCalibrationCameraCalibration, calibrate_camerascalibrate_camerasCalibrateCamerasCalibrateCamerasCalibrateCameras

Nachfolger

write_posewrite_poseWritePoseWritePoseWritePose, convert_pose_typeconvert_pose_typeConvertPoseTypeConvertPoseTypeConvertPoseType, pose_to_hom_mat3dpose_to_hom_mat3dPoseToHomMat3dPoseToHomMat3dPoseToHomMat3d, disp_caltabdisp_caltabDispCaltabDispCaltabDispCaltab, sim_caltabsim_caltabSimCaltabSimCaltabSimCaltab

Alternativen

calibrate_hand_eyecalibrate_hand_eyeCalibrateHandEyeCalibrateHandEyeCalibrateHandEye

Siehe auch

find_caltabfind_caltabFindCaltabFindCaltabFindCaltab, find_marks_and_posefind_marks_and_poseFindMarksAndPoseFindMarksAndPoseFindMarksAndPose, disp_caltabdisp_caltabDispCaltabDispCaltabDispCaltab, sim_caltabsim_caltabSimCaltabSimCaltabSimCaltab, write_cam_parwrite_cam_parWriteCamParWriteCamParWriteCamPar, read_cam_parread_cam_parReadCamParReadCamParReadCamPar, create_posecreate_poseCreatePoseCreatePoseCreatePose, convert_pose_typeconvert_pose_typeConvertPoseTypeConvertPoseTypeConvertPoseType, write_posewrite_poseWritePoseWritePoseWritePose, read_poseread_poseReadPoseReadPoseReadPose, pose_to_hom_mat3dpose_to_hom_mat3dPoseToHomMat3dPoseToHomMat3dPoseToHomMat3d, hom_mat3d_to_posehom_mat3d_to_poseHomMat3dToPoseHomMat3dToPoseHomMat3dToPose, caltab_pointscaltab_pointsCaltabPointsCaltabPointsCaltabPoints, gen_caltabgen_caltabGenCaltabGenCaltabGenCaltab, calibrate_hand_eyecalibrate_hand_eyeCalibrateHandEyeCalibrateHandEyeCalibrateHandEye

Literatur

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.

Modul

Calibration