Note: This tutorial assumes you have completed the adding a frame tutorial (Python) (C++).
(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

tfと時間について学ぶ (C++)

Description: このチュートリアルでは、tfツリーでtransformが使えるようになるまでwaitForTransformを使って待つ方法を学びます

Tutorial Level: INTERMEDIATE

Next Tutorial: Time travel with tf (C++)

tf と 時間

前回のチュートリアルで、座標系フレームのツリーをtfがどのように追っているかについて学びました。この木は、時間とともに変化し、tfはすべてのtransformの日時でスナップショットを蓄えます。(デフォルトで10秒まで)今まで、いつtransformが記録されているか知らずにtfツリーの中の最新のtransformsをlookupTransform()を使って取得しました。このチュートリアルでは、どのように特定の時間でのtransformをとるかについて学びます。

チュートリアルフレームを加えるで最後に終わったところまで戻りましょう。チュートリアルのためのパッケージに移動しましょう。:

  $ roscd learning_tf

src/turtle_tf_listener.cppを開き、25-27行あたりを見てください。

   try{
      listener.lookupTransform("/turtle2", "/carrot1",  
                               ros::Time(0), transform);

carrotではなく、2匹目の亀に1匹の亀の方を追わせるようにしましょう。以下のにコードを変更してください。

   try{
      listener.lookupTransform("/turtle2", "/turtle1",  
                               ros::Time(0), transform);

0に等しい時間があるのが見えるでしょう。tfにとって、0はバッファの中で"最も最新"であることを意味しています。 さて、現在の時刻のtransformを取得するように行を変更しましょう。:

  try{
    listener.lookupTransform("/turtle2", "/turtle1",  
                             ros::Time::now(), transform);

まず、前回のチュートリアルのlaunchファイルが止まっていることを確認してください。コードをコンパイルして、再度実行です。:

  $ catkin_make

  $ make

  $ roslaunch learning_tf start_demo.launch

すると、いきなり全てのlookupTransform()が失敗しています。それを何度も報告しています。:

[ERROR] [1412843681.552291164]: Lookup would require extrapolation into the future.  Requested time 1412843681.552039447 but the latest data is at time 1412843681.535783505, when looking up transform from frame [turtle1] to frame [turtle2]
....

なぜでしょう?異なるtf broadcasterからやってくる全ての座標変換を蓄えるバッファを、それぞれのlistenerはもっています。broadcasterがtransformを送り出したときに、バッファにtransformが入れられるのに時間がかかってしまいます。(通常数ミリ秒)。このため、"今"のフレームtransformを要求したときに、情報が到着するのに数ミリ秒待つ必要があるのです。

transformを待つ

tfは、transformが利用可能になるまでの待ちを実現する便利なツールがあります。どのようなコードになるのか見てみましょう。:

  try{
    ros::Time now = ros::Time::now();
    listener.waitForTransform("/turtle2", "/turtle1",
                              now, ros::Duration(3.0));
    listener.lookupTransform("/turtle2", "/turtle1",
                             now, transform);

waitForTransform()には4つの引数があります:

  1. 取得したい変換のfromにあたるframe
  2. 取得したい変換のtoにあたるframe
  3. 指定する時間
  4. 時間切れ: この最大の期間よりは長く待たない

Note: ros::Time::now()の使い方は、この例だけのためのものです。通常は、変換したいデータのタイムスタンプであるべきです。

したがって、waitForTransform()は実際には亀2匹の間のtransformが利用可能になるか、もしtransformが利用可能でない場合、時間切れが来るまでブロックします。

まず、前回のチュートリアルのlaunchファイルが止まっていることを確認してください。コードをコンパイルして、再度実行です。:

  $ catkin_make

  $ make

  $ roslaunch learning_tf start_demo.launch

しかし、ここでもエラーを一度見ることになるでしょう。(エラーメッセージは環境により異なります):

[ERROR] [1412843875.425070634]: Lookup would require extrapolation into the past.  Requested time 1412843872.419219169 but the earliest data is at time 1412843872.989170652, when looking up transform from frame [turtle1] to frame [turtle2]

turtlr2は、立ち上がるのに時間を要さず、tfフレームを配信し始めるのでこのようなことが起こります。ゆえに、現在の/turtle2のフレームについて要求する一番初めのときは、存在しないのでしょう。初回のtransform以降はすべて存在するので、意図したように亀が振舞います。

結果を確認する

さて、また矢印キーを用いて1匹の亀を動かすことで動作を簡単に確認できます。

これで、亀の振る舞いに確認できるような違いは出てないのがわかるでしょう。それは、実際のタイミングの違いがほんの数ミリ秒であるためです。では、なぜTime(0) からnow()への変更をしたのか?それは単に、tfのバッファとそれに関係して生じる時間の遅れについて教えておきたかったためです。実際のtfの使用の際は、Time(0)を使うのでなんら問題はありません。

これで次のチュートリアルに進む準備ができました。次は、tf内での時間移動について学びます。 (Python) (C++)

Wiki: ja/tf/Tutorials/tf and Time (C++) (last edited 2014-10-09 08:40:09 by Moirai)