1.チェックボードの印刷
研究等でカメラをやる人にはおなじみなのですが、F1のチェッカーフラッグのような
画像を見せてカメラのキャリブレーションをします。
このチュートリアルにある↓のファイルを印刷してもいいですし、
他のチェッカーでもサイズが分かっていればいいと思います。
そしてこれはそのままだと大きすぎて印刷大変でしょうから、僕はA4サイズでやりました。
チェックボードもPTAMで印刷したものがあったので、それでやっちゃいました。
2.キャリブレーションの実行
まず以下のようにして、camera_calibrationが使えるようにしましょう。
$ rosmake camera_calibration --rosdep-install
そしたら、チェッカーボードのサイズにあわせて以下のようにしてキャリブレーションプログラムを走らせます。
$ rosrun camera_calibration cameracalibrator.py --size 8x6 --square 0.108 image:=/usb_cam/image_raw
私はPTAMのcalib_pattern.pdfを使ったので、
$ rosrun camera_calibration cameracalibrator.py --size 11x7 --square 0.02 image:=/usb_cam/image_raw
でやりました。
原文にあるように最後にcamera:=/usb_camなどを付けると/usb_cam/set_camera_infoサービスを呼ぼうとするので失敗するので付けないでください。
すると↑のような画面が表示されるので、
グリグリと、いろんな方向からこのチェッカーボードをカメラで見せてください。
しばらくやっているとCALIBRATEボタンが有効になるので、これをクリックー>SAVEボタンをクリックしてください。
3.データの確認
すると
/tmp/calibrationdata.tar.gz
にキャリブレーションに使った画像ファイルとデータが保存されます。
$ tar zxvf /tmp/calibrationdata.tar.gz
すると、
left-0000.png
left-0001.png
left-0002.png
left-0003.png
left-0004.png
left-0005.png
left-0006.png
left-0007.png
left-0008.png
left-0009.png
left-0010.png
left-0011.png
left-0012.png
left-0013.png
left-0014.png
left-0015.png
left-0016.png
left-0017.png
left-0018.png
left-0019.png
left-0020.png
left-0021.png
left-0022.png
left-0023.png
left-0024.png
left-0025.png
left-0026.png
left-0027.png
left-0028.png
ost.txt
と、いろいろ出てきます。
重要なのは最後のost.txtです。
このファイルの中身は以下のようになっています。
# oST version 5.0 parameters
[image]
width
640
height
480
[narrow_stereo/left]
camera matrix
849.555669 0.000000 310.565257
0.000000 850.171143 237.409081
0.000000 0.000000 1.000000
distortion
0.270500 -1.345412 -0.000040 -0.001902 0.0000
rectification
1.000000 0.000000 0.000000
0.000000 1.000000 0.000000
0.000000 0.000000 1.000000
projection
849.555669 0.000000 310.565257 0.000000
0.000000 850.171143 237.409081 0.000000
0.000000 0.000000 1.000000 0.000000
これがカメラのパラメータになります。
以上でキャリブレーションは終わりです。
前回の続きで、ar_poseにこの結果を利用してみます。
ar_poseの実行
$ roscd ar_pose
$ cd launch
して、
以下をar_pose_single.launchのパラメータを書き換えます。
D: ost.txtのdistortion
K: ost.txtのcamera matrix
R: ost.txtのrectification
P: ost.txtのprojection
になるようにします。
<launch>
<param name="use_sim_time" value="false"/>
<node pkg="rviz" type="rviz" name="rviz"
args="-d $(find ar_pose)/demo/demo_single.vcg"/>
<node pkg="tf" type="static_transform_publisher" name="world_to_cam"
args="1 1 0.3 0 0 0 world ar_marker 10" />
<node name="usb_cam" pkg="usb_cam" type="usb_cam_node" respawn="false" output="log">
<param name="video_device" type="string" value="/dev/video0"/>
<param name="camera_frame_id" type="string" value="usb_cam"/>
<param name="io_method" type="string" value="mmap"/>
<param name="image_width" type="int" value="640"/>
<param name="image_height" type="int" value="480"/>
<param name="pixel_format" type="string" value="yuyv"/>
<rosparam param="D">[0.270500, -1.345412, -0.000040, -0.001902, 0.0000]</rosparam>
<rosparam param="K">[849.555669, 0.000000, 310.565257, 0.000000, 850.171143, 237.409081, 0.000000, 0.000000, 1.000000]</rosparam>
<rosparam param="R">[1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0]</rosparam>
<rosparam param="P">[849.555669, 0.000000, 310.565257, 0.000000, 0.000000, 850.171143, 237.409081, 0.000000, 0.000000, 0.000000, 1.000000, 0.000000]</rosparam>
</node>
<node name="ar_pose" pkg="ar_pose" type="ar_single" respawn="false" output="screen">
<param name="marker_pattern" type="string" value="data/patt.hiro"/>
<param name="marker_width" type="double" value="80.0"/>
<param name="marker_center_x" type="double" value="0.0"/>
<param name="marker_center_y" type="double" value="0.0"/>
<param name="marker_frame" type="string" value="ar_marker"/>
<param name="threshold" type="int" value="100"/>
<param name="use_history" type="bool" value="true"/>
</node>
</launch>
$ roslaunch ar_pose_single.launch
すると、USBカメラ位置がrviz上でマーカーからの相対で表示されます。
少しは精度よくなったのかな?
以上です。
0 件のコメント:
コメントを投稿