ar_poseパッケージはARToolKitの機能のうち、マーカーの位置姿勢を認識する機能だけを取り出して、TFメッセージを書き出すようにしたCCNY(City University of New York)のパッケージです。
前回はインストールまでやりました。
前回の記事でusb_camパッケージはcamera_infoトピックを発行しないのでどうしよう?
ということを書きましたが、これは古いusb_camパッケージを使っていたからで、
最新のboschのusb_camパッケージではちゃんと対応していました。
http://www.ros.org/wiki/bosch-ros-pkg#bosch_drivers
$ svn export http://bosch-ros-pkg.svn.sourceforge.net/svnroot/bosch-ros-pkg/trunk/stacks/bosch_drivers
のようにしてソフトをダウンロードし、
$ rosmake usb_cam
とすればOKですね。
ar_pose/launch/ar_pose_single.launch
を覗いてみたら、ちゃんとこのusb_camパッケージを使っていましたので、
USBカメラで簡単に試せるようになっています。
1.USBカメラの動作確認
まずはカメラをPCに差してusb_camノードを立ち上げます。
以下のようなusb.launchを用意して、
<launch>
  <node name="usb_cam" pkg="usb_cam" type="usb_cam_node" output="screen" >
    <param name="video_device" value="/dev/video0" />
    <param name="image_width" value="640" />
    <param name="image_height" value="480" />
    <param name="pixel_format" value="yuyv" />
    <param name="camera_frame_id" value="usb_cam" />
    <param name="io_method" value="mmap" />
  </node>
</launch>
$ roslaunch usb.launch
するとキャプチャ開始されると思います。
$ rosrun image_view image_view image:=/usb_cam/image_raw
とすると表示されます。されなければ、上記usb.launchの各種設定を見直してください。
確認が終わったらimage_viewは落しちゃっていいです。
動作確認が終わったらusb.launchのほうも一旦落としてください。
2.パターンの印刷
ではまず、
$ roscd artoolkit
して、
build/artoolkit-svn/patterns/pattHiro.pdf
を印刷してください。
↓です。
3.ar_poseの実行
$ roscd ar_pose
launch/ar_pose_single.launch
のusb_camノードの必要なパラメータ(pixel_formatなど)だけ書き換えて、
$ roslaunch ar_pose ar_pose_single.launch
してみましょう。
ほら、簡単でしょう?
ちなみに私の環境ではar_pose_single.launchは以下のような感じです。
<launch>
  <param name="use_sim_time" value="false"/>
        <node pkg="rviz" type="rviz" name="rviz"
          args="-d $(find ar_pose)/launch/live_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.025751483065329935, -0.10530741936574876,-0.0024821434601277623, -0.0031632353637182972, 0.0000]</rosparam>
                <rosparam param="K">[558.70655574536931, 0.0, 316.68428342491319, 0.0, 553.44501004322387, 238.23867473419315, 0.0, 0.0, 1.0]</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">[558.70655574536931, 0.0, 316.68428342491319, 0.0, 0.0, 553.44501004322387, 238.23867473419315, 0.0, 0.0, 0.0, 1.0, 0.0]</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="threshold" type="int" value="100"/>
                <param name="use_history" type="bool" value="true"/>
        </node>
</launch>
以上です。あとはTFになっているんで、焼くなり煮るなりなんとでも。。。
カメラパラメータが適当なので、それなりに表示はされていますが、位置はずれていると思います。
次回はキャリブレーションをやってみます。