Select Git revision
kalibrierung.tex 22.79 KiB
\chapter{Kamera Kalibrierung} \label{chap: kalibrierung}
Damit der später beschriebene Fahrspurerkennung möglichst zuverlässig funktioniert und möglichst reproduzierbar ist, wird eine Kalibrierung
vorgenommen. Das Vergehen dazu und die Ergebnisse sind im folgenden Kapitel dokumentiert.
\section{Intrinsische Kalibrierung} \label{sec: intrinsic}
Bedingt durch den technischen Aufbau des Linsensystems und Ungenauigkeiten bei der Herstellung sind die von der Kamera gelieferten
Bilder merklich verzehrt. In \autoref{fig: kamerabild unkalibriert} ist dies gut anhand der Linien des Schachbrettes zu erkennen, die in der
Realität natürlich alle parallel verlaufen, im Bild aber gekrümmt aussehen.
\begin{figure}
\includegraphics[width=.4\textwidth]{img/unkalibriert.png}
\caption{Unkalibriertes Kamerabild mit tonnenförmiger Verehrung}
\label{fig: kamerabild unkalibriert}
\end{figure}
\subsection{Radiale Verzerrung}
Die erste mögliche Art der Verzerrung ist die radiale Verzerrung. Diese ist die auffälligste Art der Verzerrung und wird häufig auch
\emph{Fischaugen Effekt} genannt. Bedingt durch die Brechung des Lichtes an den Kanten der Blende und der Linse entsteht eine Ablenkung
der Lichtstrahlen in der Kamera, die mit der Entfernung vom Mittelpunkt immer weiter zu nimmt. Nimmt die Ablenkung mit der Entfernung zu,
spricht man von positiver, kissenförmige Verzerrung, den umgekehrte Fall nennt man negative, tonnenförmige Verzerrung. Zur Verdeutlichung
ist in \autoref{fig: optische verzerrung} die Auswirkung dieser Verzerrung auf ein Rechteckmuster gezeigt.
\begin{figure}
\subfigure[Kissenförmige Verzerrung]{\includegraphics[page=3,width=.3\textwidth]{svg/Lens_distorsion.pdf}}
\subfigure[Verzerrungsfreies Bild]{\includegraphics[page=2,width=.3\textwidth]{svg/Lens_distorsion.pdf}}
\subfigure[Tonnenförmige Verzerrung]{\includegraphics[page=1,width=.3\textwidth]{svg/Lens_distorsion.pdf}}
\caption{Darstellung der optischen Verzerrung (nach \cite{wiki:LinsenVerzerung})}
\label{fig: optische verzerrung}
\end{figure}
Mathematisch lässt dich die Veränderung eines Punktes durch die Verzierung wie in \autoref{eq: radiale verzerrung} beschrieben berechnen.
Dabei beschreiben $x$ und $y$ die unverzerrten Pixelkoordinaten, $k_1$, $k_3$ und $k_3$ die Verzerrungskoeffizienten.
Theoretisch existieren noch weitere Koeffizienten, aber in der Praxis haben sich die ersten drei als ausreichend herausgestellt.
\cite{Hanning:highPrecisionCamCalibration}
\begin{equation}\label{eq: radiale verzerrung}
\begin{split}
x_{distored} &= x( 1 + k_1 r^2 + k_2 r^4 + k_3 r^6 ) \\
y_{distored} &= y( 1 + k_1 r^2 + k_2 r^4 + k_3 r^6 ) \\
\end{split}
\end{equation}
\pagebreak
\subsection{Tangentiale Verzerrung}
Die tangentiale Verzerrung entsteht durch kleine Ausrichtungsfehler im Linsensystem. Dadruch liegt die Linse nicht perfekt in der
Bildebene und der Bildmittelpunk sowie die Bildausrichtung können leicht verschoben sein.
\begin{figure}
\missingfigure{Sensor-Linse alignment}
\caption{Probleme in der Ausrichtung von Sensor und Linse (nach \cite{Matlab:CameraCalibration})}
\end{figure}
Mathematisch wird diese Verzerrung durch den folgenden Zusammenhang beschrieben. \cite{Hanning:highPrecisionCamCalibration}
\begin{equation}
\begin{split}
x_{distored} &= x + \left[2p_1xy + p_2(r^2 + 2x^2)\right] \\
y_{distored} &= y + \left[p_1(r^2 + 2y^2) + 2p_2xy\right] \\
\end{split}
\end{equation}
\bigskip
Durch beide Verzerrungsarten zusammen werden also durch fünf Parameter beschrieben, die sogenannten Verzerrungskoeffizienten. Historisch
begründet wird dabei $k_3$ an das Ende geschrieben, da dieses Parameter früher kaum berücksichtigt wurde.
\begin{equation}
D_{coeff} = (k_1, k_2, p_1, p_2, k_3)
\end{equation}
Um die Parameter bestimmen zu können, müssen also mindestens fünf Punkte gefunden werden, von denen die \gls{Welt-coords} und die
Bildkoordinaten bekannt sind. Da sich die Punktepaare aber nur schwer mathematisch perfekt bestimmen lassen, werden mehr Paare benötigt,
um ein überbestimmtes Gleichungssystem zu erhalten und dieses nach dem geringsten Fehler zu lösen. \cite{OpenCV:CameraCalibration}
\medskip
In der Praxis werden 2D-Muster verwendet, um Punktepaare zu bestimmen. Da sich alle Punkte dieser Muster in einer Ebene befinden, kann der
Uhrsprung der \gls{Welt-coords} in eine Ecke des Musters gelegt werden, sodass die Z-Koordinate keine Relevanz mehr hat und wegfällt.
\cite{uniFreiburg:rob2-CamCalibration}
Dabei werden Muster so gewählt, dass es möglichst einfach fällt die Weltkoordinaten der Punkte zu bestimmen. Beispielsweise sind bei einem
Schachbrettmuster die Entfernungen alle identisch und können als $1$ angenommen werden, wodurch die Koordinaten der Punkte direkt ihrer
Position im Muster entsprechen.
\section{Durchführung der intrinsischen Kalibrierung}
Zur Durchführung der Kalibrierung wir ein Python-Script erstellt, um die den Vorgang einfach und wiederholbar zu machen. Als Vorlage für
dieses dient die Anleitung zur Kamera Kalibrierung aus der \gls{OpenCV} Dokumentation \cite{OpenCV:CameraCalibration}.
Außerdem wird eine \gls{ROS Nodelet} erstellt, welches die Kalibrierung auf den Video-Stream anwendet und korrigierte Bilder veröffentlicht.
\subsection{Python Script zur Durchführung der Kalibrierung}
Grundlage für die Kalibrierung ist es, eine Reihe von Bildern mit der zu kalibrierenden Kamera aufzunehmen, auf denen sich ein
Schachbrettartiges Kalibriermuster befindet. Wichtig ist es, dasselbe Muster und dieselbe Auflösung für alle Bilder verwendet werden. Es muss
sich dabei nicht um eine quadratische Anordnung handeln, jedoch muss die Anzahl der Zeilen und spalten im Code angegeben werden. Dabei ist
allerdings nicht die Anzahle der Felder gemeint, sondern die Anzahl der inneren Kreuzungspunkten. Ein normales Schachbrett hat beispielsweise
$8 \!\times\! 8$ Felder, aber nur $7 \!\times\! 7$ interne Kreuzungen. Zur Verdeutlichung sind die Kreuzungspunkte des Verwendeten
Kalibriermuster in \autoref{fig: kalibriermuster} grün markiert.
\begin{figure}
\includegraphics[width=.4\textwidth]{img/kalibrieren_PATTER.png}
\caption{Schachbrett Kalibriermuster mit markierten inneren Kreuzungen}
\label{fig: kalibriermuster}
\end{figure}
Es wird nun ein Standard Schachbrett als Kalibriermuster verwendet, wie es bereits in \autoref{fig: kalibriermuster} zu sehen ist. Dessen
Kalibriermustergröße von $7 \!\times\! 7$ wird im Code als Konstante definiert:
\begin{lstlisting}[
float,
style=example,
caption=Definiteion der Größe des Kalibriermuster,
language=Python
]
# define the grid pattern to look for
PATTERN = (7,7)
\end{lstlisting}
Entsprechend der Anleitung \cite{OpenCV:CameraCalibration} werden benötigte Variablen initialisiert (siehe \autoref{code: kali var init}).
\begin{lstlisting}[
float,
style=example,
caption=Initialisierung von Variablen für die Kalibreirung,
language=Python,
label=code: kali var init
]
# termination criteria
criteria = (cv.TERM_CRITERIA_EPS + cv.TERM_CRITERIA_MAX_ITER, 30, 0.001)
# prepare object points, like (0,0,0), (1,0,0),...,(6,5,0)
objp = np.zeros((PATTERN[0]*PATTERN[1],3), np.float32)
objp[:,:2] = np.mgrid[0:PATTERN[0],0:PATTERN[1]].T.reshape(-1,2)
# Arrays to store object points and image points from all the images.
objpoints = [] # 3d point in real world space
imgpoints = [] # 2d points in image plane.
\end{lstlisting}
Nun werden alle im aktuellen Ordner befindlichen Bilder eingelesen und in einer Liste abgespeichert. Jedes Listenelement wird eingelesen und
in ein Schwarzweißbild umgewandelt. Dieses wird dann an die \gls{OpenCV} Funktion \lstinline{findChessboardCorners()} übergeben, welche die
Kreuzungspunkten findet und zurückgibt.
\begin{lstlisting}[
float,
style=example,
caption=Finden und Verarbeiten der Kalibrierbilder,
language=Python
]
# get all images in current directory
folder = pathlib.Path(__file__).parent.resolve()
images = glob.glob(f'{folder}/*.png')
# loop over all images:
for fname in images:
img = cv.imread(fname)
gray = cv.cvtColor(img, cv.COLOR_BGR2GRAY)
# Find the chess board corners
ret, corners = cv.findChessboardCorners(gray, PATTERN, None, flags=cv.CALIB_CB_ADAPTIVE_THRESH)
\end{lstlisting}
Dabei ist es gar kein Problem, wenn nicht in jedem Bild das Kalibriermuster gefunden werden kann, solange insgesamt ausreichend nutzbare
Bilder vorhanden sind. Bei nicht nutzbaren Bildern gibt \lstinline{findChessboardCorners()} \lstinline{None} zurück und das Bild wird einfach
übersprungen.
Für alle nutzbaren Bilder werden die in \autoref{code: kali var init} erstellten Punktbezeichnungen zur Liste der gefundenen Objekte
hinzugefügt. Die Genauigkeit der gefunden Eckkoordinaten wird über die Funktion \lstinline{cornerSubPix()} erhöht und diese werden an die
Liste der gefundenen Bildpunkte angehängt.
\begin{lstlisting}[
float,
style=example,
caption=Abspeichern der Gefundenen Bildpunkte,
language=Python
]
# If found, add object points, image points
if ret == True:
objpoints.append(objp)
corners2 = cv.cornerSubPix(gray,corners, (11,11), (-1,-1), criteria)
imgpoints.append(corners)
\end{lstlisting}
Jetzt kann die eigentliche Kalibrierung mittels der \gls{OpenCV} Funktion \lstinline{calibrateCamera()} durchgeführt werden. Diese nimmt
die zuvor erstellten Listen von Objektkoordinaten und Bildpunkten und löst damit die in \autoref{sec: intrinsic} beschriebenen
Gleichungen. Als Ergebnis liefert sie die Kameramatrix $K$ und die Verzerrungskoeffizienten $D_{coeff}$ zurück.
\cite{OpenCV:CameraCalibration}
\begin{lstlisting}[
float,
style=example,
caption=Ermitteln der Kalibrierwerte mittels OpenCV,
language=Python
]
# get calibration parameters:
ret, K, D_coeff, rvecs, tvecs = cv.calibrateCamera(objpoints, imgpoints, gray.shape[::-1], None, None)
\end{lstlisting}
Der gesamte Code wird nun auf einen Datensatz von Bilder angewandt, um die Ergebnisse für den vorliegenden Roboter zu erhalten. Der
Datensatz ist auf dem GitLab Server unter der \cite{git:dataset-kalibreirung} abgelegt. Damit ergeben sich die folgenden
Kalibrierungsergebnisse.
\begin{align*}
k_1 &= -0,42049309612684654 \\
k_2 &= 0,3811654512587829 \\
p_1 &= -0,0018273837466050299 \\
p_2 &= -0,006355252159438178 \\
k_3 &= -0,26963105010742416 \\
K &=
\begin{pmatrix}
384,65 & 0 & 243,413 \\
0 & 384,31 & 139,017\\
0 & 0 & 1 \\
\end{pmatrix}
\end{align*}
Um zu zeigen, wie sich das Bild damit verbessern lässt, werden die Ergebnisse auf eines der Bilder angewandt. Da sich die Abmessungen des
entzerrten Bildes von denen des Verzehrten unterscheiden, wird zuerst die \gls{OpenCV} Funktion \lstinline{getOptimalNewCameraMatrix()}
verwendet, welche eine weiter Skalierte Kameramatrix ermittelt, mit der die Abmessungen zueinander passen. Diese liefert außerdem eine
\gls{ROI}, also den Bildbereich der nur relevante (nicht leere) Pixel enthält.
Mit dieser zusätzlichen Matrix kann nun die \gls{OpenCV} Funktion \lstinline{undistort()} auf das Bild angewandt werden. Diese Produziert das
entzerrte Bild mit leeren Pixeln in den Bereichen, wo keine Informationen im Originalbild vorlagen. Um diese leeren Pixel zu entfernen wird
das Bild auf die \gls{ROI} reduziert.
\medskip
In \autoref{fig: intrinsik schritte} ist die Entzerrung des Beispielbildes mit dem Zwischenschritt mit Leerpixeln gezeigt.
\begin{figure}
\includegraphics[width=\textwidth]{img/kalibrieren_schritte.png}
\caption{Schritte der intrinsischen Kalibrierung}
\label{fig: intrinsik schritte}
\end{figure}
\subsubsection{Reprojektions-Fehler}
Um eine Aussage über die Genauigkeit der gefundenen Kalibrierungs-Parameter treffen zu können, wird der Reprojektions-Fehler bestimmt.
Dieser gibt den Abstand zwischen einem im Kalibriermuster gefundenen Kreuzungspunkt und den mittels der Kalibrierung Ergebnisse
berechneten \gls{Welt-coords}. Der Mittelwert aller Abweichungen in allen verwendeten Bilder gibt den Reprojektions-Fehler für den
ganzen Kalibriervorgang an.
Der \autoref{code: reprojektions fehler} zeigt die Berechnung mittels von OpenCV zur Verfügung gestellten Funktionen und den zuvor
ermittelten Kalibrierdaten. Für jeden Satz an theoretischen \gls{Welt-coords} des Kalibriermusters in \lstinline{objpoints} werden
die Punkte im Bild mit der OpenCV Funktion \lstinline{projectPoints()} bestimmt und mit den gefundenen Punkten verglichen. Dazu wird
die OpenCV Funktion \lstinline{norm()} verwendet, die direkt die summe aller Differenzen zweigen den beiden Punktelisten liefert.
Das Ergebnis wird auf dem Bildschirm ausgegeben.
\begin{lstlisting}[
float,
style=example,
caption=Berechnen des Reprojektions-Fehlers,
label=code: reprojektions fehler,
language=Python
]
# calculate re-projection error
mean_error = 0
for i in range(len(objpoints)):
imgpoints2, _ = cv.projectPoints(objpoints[i], rvecs[i], tvecs[i], mtx, dist)
error = cv.norm(imgpoints[i], imgpoints2, cv.NORM_L2)/len(imgpoints2)
mean_error += error
print(f"total error: {mean_error/len(objpoints)}")
\end{lstlisting}
Mit dem verwendeten Datensatz ergibt sich ein Reprojektions-Fehler von $0,049$, was genau genug für diesen Anwendungsfall ist.
\subsection{Anwenden der Kalibrierung in einer ROS Node} \label{sec: undistort Node}
Um die Kalibrierungsergebnisse auf jedes Bild, dass vom Kamera Treiber veröffentlicht wird, anzuwenden, wird eine weitere \gls{ROS Node}
erstellt. Diese entzerrt jedes erhaltene Bild und veröffentlicht die korrigierte Version als eigens \gls{Topic}. Das korrigierte Bild wird
sowohl in Farbe als auch in Schwarz-Weiß veröffentlicht. Die Beziehung der \glspl{Topic} ist in \autoref{fig: topics graph undistoreter node}
Grafisch dargestellt.
\begin{figure}
\includegraphics[scale=.9]{svg/Topics_undistorter.pdf}
\caption{Beziehungen der entzerrer Node zu bestehenden Nodes}
\label{fig: topics graph undistoreter node}
\end{figure}
\subsubsection{Initialisieren der Node}
Beim Start der \gls{ROS Node} wird die \lstinline{main()} Funktion aufgerufen, welche die notwendigen \gls{ROS} Funktionen zur
Initialisierung aufruft, das benötigt \gls{Topic} abonniert, ein \gls{Callback} anhängt und die eigenen \glspl{Topic} veröffentlicht.
\todo{Code hierzu?}
Außerdem werden die Kalibrierdaten aus einer Konfigurationsdatei im YAML-Format eingelesen und in variablen übernommen. Die
Verzerrungsparameter werden als Vektor eingelesen und die Kameramatrix wird in eine \gls{OpenCV} Matrix umgewandelt. Außerdem wird die
Bildgröße benötigt und aus der Konfigurationsdatei gelesen. \autoref{code: intrinsic einlesen YAML} zeigt den Ablauf. Es ist sinnvoll,
dies bereits in der \lstinline{main()} Funktion durchzuführen, um die \gls{Callback} zu entlasten und dort Rechenzeit einzusparen.
\begin{lstlisting}[
float,
style=example,
caption=Einlesen der Kalibrierungsergebnisse aus einer YAML-Datei,
label=code: intrinsic einlesen YAML,
language=C++
]
// open YAML-file and get config
std::string configFilePath = "./tools/calibration/calibration.yaml";
YAML::Node full_config = YAML::LoadFile(configFilePath);
YAML::Node camera_config = full_config["cameras"]["default"];
// read distorion coeffitiones and convert to OpenCV vector
auto distortion_YAML = camera_config["intrinsic"]["distortion"] .as<std::vector<double>>();
cv::Mat distortion ( distortion_YAML );
// read camera matrix and convert to OpenCV matrix
auto cameraMatrix_YAML = camera_config["intrinsic"]["matrix"] .as<std::vector<std::vector<double>>>();
cv::Mat cameraMatrix = toMat( cameraMatrix_YAML );
// read image size
cv::Size imageSize(
full_config["images"]["size"]["width"].as<int>(),
full_config["images"]["size"]["height"].as<int>()
);
\end{lstlisting}
Mit diesen Werten können nun \emph{Mappings} erzeugt werden, welche die geometrische Beziehung zwischen einem Pixel im Originalbild und
einem Pixel im entzerrten Bild abspeichern. Es werden zwei \emph{Mappings} für die X und die Y-Koordinate erzeugt, welche in globalen
Variablen abgelegt werden. Das ist notwendig damit die Informationen der \gls{Callback} zur Verfügung stehen.
Zuvor ist es aber noch sinnvoll, eine umskalierte, optimierte Kameramatrix zu erzeugen. \gls{OpenCV} stellt hierzu die Funktion
\lstinline{getOptimalNewCameraMatrix()} zur Verfügung. Diese erstellt die neue Matrix abhängig von einem freien Skalierungsparameter
$\alpha$. Für $\alpha=0$ ist die zurückgegebene Matrix so gewählt, dass das entzerrte Bild möglichst wenig unbekannte Pixel enthält. Das
bedeutet aber, dass einige Pixel des Originalbildes außerhalb des neuen Bildbereiches liegen und vernachlässigt werden. Mit $\alpha=1$
enthält das entzerrte Bild alle Pixel des Originalbildes, allerdings bleiben einige Pixel schwarz. Da die Funktion zusätzlichen eine
\gls{ROI} liefert, welches den Bildausschnitt ohne schwarze Pixel beschreibt, wird hier $\alpha=1$ verwendet. Die veröffentlichten Bilder
werden zwar auf die \gls{ROI} reduziert, aber die vorhanden Informationen werdenden grundsätzlich erhalten und bei Bedarf kann das
Programm einfach angepasst werden, um die vollständigen Bilder zu veröffentlichen.
\begin{lstlisting}[
float,
style=example,
caption=Bestimmen der Pixel-Mappings zu Entzerrung,
language=C++
]
// get scaled camera matrix
auto scaledCameraMatrix = cv::getOptimalNewCameraMatrix(cameraMatrix, distortion, imageSize, 1, imageSize, &ROI);
// calculate undistortion mappings
cv::initUndistortRectifyMap(cameraMatrix, distortion, cv::Mat(), scaledCameraMatrix, imageSize, CV_16SC2, rectifyMapX, rectifyMapY);
\end{lstlisting}
\subsubsection{Callback-Funktion zur Handhabung der Einzelbilder}
Die \gls{Callback} \lstinline{callback_undistort_image()} wurde während der Initialisierung an das \gls{Topic} \lstinline{/img/raw}
angehängt und wird nun für jedes dort veröffentlichte Bild aufgerufen. Der \autoref{code: undistort callback} zeigt eine vereinfachte
Version der Implementierung, ohne Umwandlung in ein Schwarzweißbild und ohne Laufzeitmessung.
Da das Bild als \gls{ROS} eigener Datentyp übergeben wird, muss es zuerst in ein mit \gls{OpenCV} kompatibles Format umgewandelt
werden. Die dazu notwendigen Funktionen sind im \gls{ROS}-Paket \lstinline{cv_bridge} zur Verfügung gestellt. Dessen Funktion
\lstinline{toCvCopy()} kopiert die Daten des Originalbildes in eine OpenCV Matrix, welche weiter verwendet werden kann.
Das Bild kann nun mit der OpenCV Funktion \lstinline{remap()} entzerrt werden. Diese benutzt die zuvor bestimmten \emph{Mappings}, um
jeden Pixel des Originalbildes an die korrekte Position im entzerrten Bild zu übertragen. Dabei wird linear interpoliert.
Das Erhalten Bild wird auf die \gls{ROI} reduziert und unter dem \gls{Topic} \lstinline{\img\color} veröffentlicht. Außerdem wird ein
Schwarz-Weiß Version erzeugt und diese als \lstinline{\img\gray} veröffentlicht (was hier aber nicht gezeigt ist).
\begin{lstlisting}[
float,
style=example,
caption=Vereinfachte Version der \gls{Callback} zur Durchführung der Entzerrung,
label=code: undistort callback,
language=C++
]
void callback_undistort_image(sensor_msgs::Image original) {
cv::Mat undistoredImage;
// convert from ROS msg-type to opencv matrix
cv_bridge::CvImagePtr imagePtr = cv_bridge::toCvCopy(original);
// apply the calculated maps to undistort the image
cv::remap(imagePtr->image, undistoredImage, rectifyMapX, rectifyMapY, cv::INTER_LINEAR);
// crop relevant section from image
undistoredImage = undistoredImage(ROI);
// publish images
cv_bridge::CvImage colorImage(std_msgs::Header(), "rgb8", undistoredImage);
pub_colorImage->publish(colorImage.toImageMsg());
}
\end{lstlisting}
\pagebreak
\subsubsection{Performance Betrachtung}
Da diese \gls{ROS Node} eine Grundlagenfunktion darstellt und parallel zu jeder anderen Anwendungen laufen muss, ist es wichtig, dass
sie möglichst Performant ist und wenig Ressourcen des JetBots verbraucht.
Daher wurde die mittlere CPU Auslastung und die durchschnittliche Laufzeit der \gls{Callback}, welche ja für jedes Bild durchlaufen
wird, gemessen.
\begin{figure}
\includegraphics[width=.6\textwidth, trim={0 0 12px 31px}, clip]{img/jtop_camera.png}
\caption{CPU Auslastung des JetBots mit laufender Kamera und entzerrer \gls{ROS Node}}
\label{fig: jtop cam+undist}
\end{figure}
Der \lstinline{jtop} Screenshot in \autoref{fig: jtop cam+undist} zeigt die CPU Nutzung bei aktivem ROS-Core, Kameratreiber und
der neu erstellten Entzerrer \gls{ROS Node}. Die durchschnittliche CPU Auslastung liegt bei ungefähr $38,75\,\percent$, ist also nur
sehr geringfügig höher als die in \autoref{sub: performance baseline} gemessene Grundauslastung ohne die neue \gls{ROS Node}.
Um die Laufzeit der \gls{ROS Node} zu bestimmen wird die aktuelle Zeit wie sie von der Funktion \lstinline{ros::Time::now()}
zurückgegeben wird verwendet. Die aktuelle Zeit beim Start der \gls{Callback} wird abgespeichert. Nach Durchlauf der Funktion wird
erneut die aktuelle Zeit bestimmt und die Differenz in Sekunden als Debug-Nachricht ausgegeben. Die Laufzeit der \gls{ROS Node} wird
über einige Zeit gemittelt. Dabei ergibt sich eine Laufzeit von $\approx 3,9\,\ms$.
\begin{table}
\caption{Gemessene Laufzeit bei 10 Durchläufen der \gls{Callback}}
\begin{tabular}{r|S}
Durchlauf Nr. & \multicolumn{1}{c}{gemessene Laufzeit} \\\hline
1 & 3,885214 \,\ms \\
2 & 4,068192 \,\ms \\
3 & 3,968679 \,\ms \\
4 & 3,711925 \,\ms \\
5 & 3,969982 \,\ms \\
6 & 4,085944 \,\ms \\
7 & 4,024673 \,\ms \\
8 & 3,897130 \,\ms \\
9 & 3,752863 \,\ms \\
10 & 4,095999 \,\ms \\
\end{tabular}
\todo[inline]{ist die Tabelle überhaupt sinnvoll?}
\end{table}
\section{Extrinsische Kalibrierung} \label{sec: extrensic}