## repository: geometry <<PackageHeader(tf)>> <<TableOfContents(3)>> {{attachment:frames2.png||height="431px",width="498px"}} == tfは何をしてなぜ使うのか? == 急いでいる方はこちら→[[tf/Tutorials/Introduction to tf|tfのデモ]] ロボットシステムでは、一般的に、たくさんのワールドフレーム、ベースフレーム、グリッパーフレーム、ヘッドフレームなどなどの常に変化する[[geometry/CoordinateFrameConventions| 座標系フレーム]]を持ちます。tfは常にこれらのフレームをトラックし、以下のようなことを聞きだせるようにしています。 * 5秒前のworldフレームから見たheadフレームはどこ? * 基準に対してロボットの手にあるオブジェクトの形はどのような姿勢になっている? * マップフレームの中でベースフレームはどのような姿勢を今とっている? tfは'''ディストリビューテッドシステム'''の中で操作できます。これは、ロボットの座標系フレームに関するすべての情報はシステムの中のすべてのコンピュータのROSのコンポーネントで利用できることを意味します。このtfの情報(transform information)にとっては中心のサーバーとなるものは存在しません。 デザインに関する詳しいことは[[/Design]]をご覧ください。 == チュートリアル == 一歩一歩tfを使って学べる[[ja/tf/Tutorials|tutorials]]のセットを作りました。[[ja/tf/Tutorials/Introduction to tf|introduction to tf]]のチュートリアルからはじめられます。すべてのtfとtfに関する完全なチュートリアルについては[[tf/Tutorials|tutorials]]をご覧ください。 ユーザがtfを使う際に欠かせない2つのことがあります。transofrmsを監視することと、それを報告することです。 tfを使っている人はみんな、transformsの情報を見ておく必要があります。 * '''transformsの情報を聞く''' - システムに ブロードキャストされているすべての座標系フレームを受け取り、バッファにため、フレーム間の特定のtransformsを求めます。tfリスナーのチュートリアル[[tf/Tutorials/Writing a tf listener (Python)|(Python)]] [[tf/Tutorials/Writing a tf listener (C++)|(C++)]]をご確認ください。 ロボットのキャパシティを広げるために、transformsを送り出す必要がでてくるでしょう。 * '''transformsをブロードキャストする''' - 他のシステムに対して、座標系フレームの相対的な姿勢を送り出します。システムはロボットの違う部分についての情報をそれぞれ吐き出す複数のブロードキャスターを持つこともできます。tfのブロードキャスターを書くチュートリアル[[tf/Tutorials/Writing a tf broadcaster (Python)|(Python)]] [[tf/Tutorials/Writing a tf broadcaster (C++)|(C++)]]をご覧ください。 基本的なチュートリアルを終えたなら、tfと時間について学びにいけます。tfと時間のチュートリアル[[tf/Tutorials/tf and Time (Python)|(Python)]] [[tf/Tutorials/tf and Time (C++)|(C++)]]では、tfと時間についての基本的な原理について学べます。tfと時間についての発展的なチュートリアル[[tf/Tutorials/Time travel with tf (Python)|(Python)]] [[tf/Tutorials/Time travel with tf (C++)|(C++)]]ではtfとともに時間を操作する原理について学べます。 == APIコード概要 == <<Include(tf/Overview)>> == よくある質問 == * [[tf/FAQ|よくある質問]] * [[geometry/RotationMethods|回転に関する関数]] * [[geometry/CoordinateFrameConventions | 座標系フレームに関するお約束]] == コマンドラインツール == tfは主にROSの[[Nodes|nodes]]の中で使われること意図して作られたライブラリですが、デバッグやtfの座標系フレームのサポートをするたくさんのコマンドラインツールがあります。 これらの中には以下のようなものがあります。 * [[#view_frames|view_frames]]: 座標系フレーム全体のツリーを可視化する。 * [[#tf_monitor|tf_monitor]]: フレーム間でのtransformsを監視する。 * [[#tf_echo|tf_echo]]: 特定のtransformを画面に表示する。 * [[roswtf]]: `tfwtf`のプラグインを用いて、tfについての問題をトラックするのをサポートします。 * [[#static_transform_publisher|static_transform_publisher]]は静的なtransformsを送るコマンドラインツールです。 座標変換をリマップするのに便利な[[#tf_remap|tf_remap]]というnodeを使いたいかもしれません。 <<Anchor(tf_monitor)>> === tf_monitor === `tf_monitor` コンソールに現在の座標変換の情報を表示します。例えば、 {{{ $ rosrun tf tf_monitor RESULTS: for all Frames Frames: Frame: /base_footprint published by /robot_pose_ekf Average Delay: 0.0469324 Max Delay: 0.0501503 Frame: /base_laser_link published by /robot_state_publisher Average Delay: 0.00891066 Max Delay: 0.009591 Frame: /base_link published by /robot_state_publisher Average Delay: 0.00891147 Max Delay: 0.009592 0.00891431 Max Delay: 0.009595 ... editing for the sake of brevity ... Broadcasters: Node: /realtime_loop 94.7371 Hz, Average Delay: 0.000599916 Max Delay: 0.001337 Node: /robot_pose_ekf 30.8259 Hz, Average Delay: 0.0469324 Max Delay: 0.0501503 Node: /robot_state_publisher 25.8099 Hz, Average Delay: 0.0089224 Max Delay: 0.00960276 }}} `tf_monitor <source_frame> <target_target>` 特定の変換を監視します。例えば、`/base_footprint`からの`/odom`への変換を監視します: {{{ $ rosrun tf tf_monitor /base_footprint /odom RESULTS: for /base_footprint to /odom Chain currently is: /base_footprint -> /odom Net delay avg = 0.00371811: max = 0.012472 Frames: Frame: /base_footprint published by /robot_pose_ekf Average Delay: 0.0465218 Max Delay: 0.051754 Frame: /odom published by /realtime_loop Average Delay: 0.00062444 Max Delay: 0.001553 Broadcasters: Node: /realtime_loop 95.3222 Hz, Average Delay: 0.00062444 Max Delay: 0.001553 Node: /robot_pose_ekf 30.9654 Hz, Average Delay: 0.0465218 Max Delay: 0.051754 Node: /robot_state_publisher 25.9839 Hz, Average Delay: 0.00903061 Max Delay: 0.00939562 }}} <<Anchor(tf_echo)>> === tf_echo === `tf_echo <source_frame> <target_frame>` `source_frame` と `target_frame`の間の特別な変換に関する情報を表示します。例えば、`/map`と`/odom`の間の変換を表示するには、 {{{ $ rosrun tf tf_echo /map /odom At time 1263248513.809 - Translation: [2.398, 6.783, 0.000] - Rotation: in Quaternion [0.000, 0.000, -0.707, 0.707] in RPY [0.000, -0.000, -1.570] }}} <<Anchor(static_transform_publisher)>> === static_transform_publisher === `static_transform_publisher x y z yaw pitch roll frame_id child_frame_id period_in_ms` x/y/z のオフセット と yaw/pitch/rollを用いてtfに対して静的な座標変換をパブリッシュします。ミリセカンドでどれほどの頻度で変換を送るかを決めます。100ms (10hz)ぐらいがよい値です。 `static_transform_publisher x y z qx qy qz qw frame_id child_frame_id period_in_ms` x/y/z のオフセット と quaternionを用いてtfに対して静的な座標変換をパブリッシュします。ミリセカンドでどれほどの頻度で変換を送るかを決めます。100ms (10hz)ぐらいがよい値です。 `static_transform_publisher`は静的な変換をセットするのに手動で使うコマンドラインツールと[[roslaunch]]ファイルとして使う場合の両方のためにデザインされています。 例えば、 {{{#!xml <launch> <node pkg="tf" type="static_transform_publisher" name="link1_broadcaster" args="1 0 0 0 0 0 link1_parent link1 100" /> </launch> }}} <<Anchor(view_frames)>> === ビューフレーム:view_frames === `view_frames` `view_frames`は現在のtransformツリーのPDFグラフを作るデバッグツールです。 実行するには: {{{ $ rosrun tf view_frames}}} 作業を終えたたら、グラフを見たくなると思います。Ubuntuシステムの典型的な使い方は、以下のようにします。 : {{{ $ rosrun tf view_frames $ evince frames.pdf }}} === roswtf プラグイン === `roswtf` tfは`roswtf`を実行するときはいつでも自動的に実行される[[roswtf]]のプラグインとともに立ち上がります。このプラグインは、現在のtfの設定を検査して、何か問題がないか探しだそうとします。実行するに際するには、単に`roswtf` と打ってください: {{{ $ roswtf }}} == ノード:Nodes == <<Anchor(tf_remap)>> {{{ #!clearsilver CS/NodeAPI node.0 { name = tf_remap desc = tf_remap は`tf_old`のトピックから情報を受け取り、`/tf`のトピックに対してtransformsを再パブリッシュします。これは、おもに座標フレームIDが更新されることが必要とされる古い[[Bags|バグ ファイル]]と共に使われます。このnodeに対しよく行われることは、`/tf:=/tf_old`の設定のもとでバグファイルを実行することです。`tf_remap`のnodeは、フレームIDを古いのから新しいものへマッピングをすることを記述する`~mappings`のパラメータとともに実行します。 sub { 0.name = /tf_old 0.type = tf/tfMessage 0.desc = 古いtransformのtreeです。これは、通常[[Bags|バグファイル]]のリプレイをリマップすることによって、パブリッシュされるものです。バグファイルのtransformsが受け入れらるようにするには、use_sim_timeをtrueにする必要があります。 } pub { 0.name = /tf 0.type = tf/tfMessage 0.desc = 現在のtransformのtreeです。これがよく見る`/tf` topicのことです. } param { 0.name = ~mappings 0.type = [ {str: str} ] 0.desc = 古いtfのframe IDと新しいtfのfrmae IDを対応付ける辞書式のリストです。リストの中の各々データは"old" と "new"のキーがあります。 0.default = [] } } }}} <<Anchor(change_notifier)>> {{{ #!clearsilver CS/NodeAPI node.0 { name = change_notifier desc = `change_notifier`は`/tf`を管理しており、定期的に`/tf_changes`のtopicによって変更された全てのtransformsを再パブリッシュします。 sub { 0.name = /tf 0.type = tf/tfMessage 0.desc = transformのtreeです。 } pub { 0.name = /tf_changes 0.type = tf/tfMessage 0.desc = コンパクトなtransformのtreeです. } param { 0.name = ~polling_frequency 0.type = float 0.desc = transformのtreeに起こった変化をチェックする周期の周波数(hz) 0.default = 10.0 1.name = ~translational_update_distance 1.type = float 1.desc = transformが変化したと判断される2枚のフレーム間の最小距離 1.default = 0.1 2.name = ~angular_update_distance 2.type = float 2.desc = transformが変化したと判断される2枚のフレーム間の回転に関する最小角度 2.default = 0.1 } } }}} ## CategoryPackage ## M3Package # Keywords Transformation, Transformations, coordinate transform