Note: This tutorial assumes you have completed the tf and time (Python) (C++) tutorials.
(!) 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における発展的な時間移動について学びます

Tutorial Level: ADVANCED

前回のチュートリアルでは、tfに置ける基本的な時間の概念について学びました。このチュートリアルでは、更にそれを発展させ、強力なtfの能力をお見せしましょう。

時間移動

前回のチュートリアルの中で終わったところから始めましょう。まず、いつもどおりパッケージの中に移ります。

  $ roscd learning_tf

src/turtle_tf_listener.cppのファイルを開きます. 25-30行目を見てください:

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

ここで、1匹目の亀がいるところを2匹目に追わせる代わりに、5秒前にいたところを追うようにしてみましょう。:

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

今、これを実行したら、どのようなものが見えると思いますか?明らかに最初の5秒間については、2匹目はどこに行けば分からないというのは、1匹目の亀の5秒間の履歴が無いことからわかります。では5秒経つとどうなるでしょう。実際に試して見ましょう。:

  $ make  or  catkin_make
  $ roslaunch learning_tf start_demo.launch
  • random.png

亀はスクリーンショットのように途方もなく動き回っていますか?さて、これは何が起きているのでしょうか?

  • 我々がtfに問い合わせたことは「5秒前の /turtle2 のポーズに対する、5秒前の /turtle1 のポーズはどのようなものか?」です。これだと、現在の /turtle2 を、 5秒前の /turtle2/turtle1 の状態に基づいてコントロールしている、ということになってしまいます。

  • しかし本当に問い合わせるべきなのは、「現在の /turtle2 のポーズに対する、 5秒前の /turtle1 のポーズはどのようなものか?」です。

lookupTransformのより発展的なAPI

どのようにしたら上記のような要求を送ることができるでしょうか?実はこのAPIは、いつ各フレームが発せられたかを正確に知らせてくれます。コードを実際に見てみましょう。

  try{
    ros::Time now = ros::Time::now();
    ros::Time past = now - ros::Duration(5.0);
    listener.waitForTransform("/turtle2", now,
                              "/turtle1", past,
                              "/world", ros::Duration(1.0));
    listener.lookupTransform("/turtle2", now,
                             "/turtle1", past,
                             "/world", transform);

lookupTransformのより発展的なAPIは6つの引数をもちます。

  1. 取得したいtransformのfromにあたるフレーム,
  2. fromの指定された時間
  3. 取得したいtransformのtoにあたるフレーム,
  4. toの指定された時間
  5. 時間がたっても変わらないフレームを指定する。ここでは'/world'
  6. 取得したtransformを蓄える変数.

waitForTransform()lookupTransform()と同じように基本と発展的なAPIをもちます。

  • time_travel.png

これの値は、tfが裏側で何をやっているかを表しています。過去においては、1匹目からworldへのtransformを計算し、worldフレームの中で、過去から今までへの時間を移動し、現在になったところで、worldから2匹目の亀へのtransformを計算します。

結果を確認する

シミュレータをもう一度実行してみましょう。

  $ make  or catkin_make
  $ roslaunch learning_tf start_demo.launch

これで、確かに、2匹目の亀は5秒前に1匹目がいたところを追従するようになりました!

Wiki: ja/tf/Tutorials/Time travel with tf (C++) (last edited 2016-11-06 11:38:17 by ronekko)