Skip to content

Commit

Permalink
Cli tools documentation (#653)
Browse files Browse the repository at this point in the history
Signed-off-by: CursedRock17 <mtglucas1@gmail.com>
  • Loading branch information
CursedRock17 authored May 22, 2024
1 parent dd30056 commit c9ca2ca
Show file tree
Hide file tree
Showing 15 changed files with 286 additions and 67 deletions.
File renamed without changes.
File renamed without changes.
153 changes: 153 additions & 0 deletions tf2_ros/doc/cli_tools.rst
Original file line number Diff line number Diff line change
@@ -0,0 +1,153 @@
Command Line Tools
==================

There are a number of tools to help you debug tf related problems. Most of them are located inside the bin directory or the scripts directory. This page gives a description of each tool, and explains what type of problems you can resolve with each tool.

Frame Poses
-----------

1. tf2_echo
^^^^^^^^^^^
``tf2_echo`` is the simplest tool to look at the numeric values of a specific transform. ``tf2_echo`` takes two arguments: the source frame and the target frame. The output of ``tf2_echo`` is the target frame in comparison to the source frame. E.g. to get the transformation from turtle1 to turtle2, set up the turtlesim example with:

.. code-block:: bash
git clone https://github.com/ros/geometry_tutorials.git -b ros2
Then build and source in each terminal:

.. code-block:: bash
colcon build && . install/setup.zsh
Then:

.. code-block:: bash
ros2 launch turtle_tf2_py turtle_tf2_demo.launch.py
Also in a separate terminal, begin controlling the robot:

.. code-block:: bash
ros2 run turtlesim turtle_teleop_key
Now using tf2_echo to take a look at the different transformations occurring between two frames

.. code-block:: bash
ros2 run tf2_ros tf2_echo turtle1 turtle2
The expected output looks something like this:

.. code-block:: bash
At time 1253924110.083
- Translation: [-1.877, 0.415, 0.000]
- Rotation: in Quaternion [0.000, 0.000, -0.162, 0.987]
in RPY [0.000, -0.000, -0.325]
At time 1253924111.082
- Translation: [-1.989, 0.151, 0.000]
- Rotation: in Quaternion [0.000, 0.000, -0.046, 0.999]
in RPY [0.000, -0.000, -0.092]
2. RViz2
^^^^^^^^
Run `rviz2` with `tf` enabled and begin viewing frames to see transforms

.. image:: images/rviz2_screenshot.png

TF tree inspection
------------------
1. Viewing TF trees
^^^^^^^^^^^^^^^^^^^
1.1 Save as a file by view_frames
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
View frames can generate a pdf file with a graphical representation of the complete tf tree. It also generates a number of time-related statistics. To run view frames, type:

.. code-block:: bash
ros2 run tf2_tools view_frames
In the current working folder, you should now have a file called "frames_$(data)_$(time).pdf". Open the file, you should see something like this:

.. image:: images/view_frames.png

Fields
~~~~~~
* Recorded at time: shows the absolute timestamp when this graph was generated.
* Broadcaster: gives the name of the node that broadcasted the corresponding transform.
* Average rate: gives the average frequency at which the broadcaster sent out the corresponding transform. Note that this is an average, and does not guarantee that the broadcaster was sending transforms the whole time.
* Buffer length: tells you how many seconds of data is available in the tf buffer. When you run view frames without specifying a node, this buffer length should be about 5 seconds.
* Most recent transform: states how long ago the last transform was received. This is the time delay of a transform.
* Oldest transform: states how long ago the first transform was received.

1.2 Query a running node
~~~~~~~~~~~~~~~~~~~~~~~~
If a specific node is having trouble its exact data can be queried using the following command:

.. code-block:: bash
ros2 run tf2_tools view_frames --node=NODE_NAME
1.3 Dynamically inspect during runtime
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
`rqt_tf_tree <https://github.com/ros-visualization/rqt_tf_tree/tree/master>`_ provides a GUI to inspect tf tree during runtime.

A simple tree from the tutorial in 1. shows that ``tf2_echo`` looks like:

.. image:: images/rqt_tf_tree.png

2. tf2_monitor
^^^^^^^^^^^^^^
``tf2_monitor`` can give you a lot of detailed information about a specific transformation you care about. The monitor will break down the chain between two frames into individual transforms, and provide statistics about timing, broadcasters, etc.

E.g. you want more information about the transformation between the frame "turtle1" and the frame "turtle2", simply type:

.. code-block:: bash
ros2 run tf2_ros tf2_monitor turtle1 turtle2
The output should look something like this:

.. code-block:: bash
RESULTS: for turtle1 to turtle2
Chain is: turtle2
Net delay avg = 0.00296015: max = 0.0239079
Frames:
Frame: turtle2, published by <no authority available>, Average Delay: 0.00385465, Max Delay: 0.00637698
Broadcasters:
Node: /turtle1_tf_broadcaster 40.01705 Hz, Average Delay: 0.0001427 Max Delay: 0.0003479
Node: /turtle2_tf_broadcaster 40.01705 Hz, Average Delay: 0.0001515 Max Delay: 0.00034
Each of these frames can be published by a different broadcaster.

3 TF Manipulation
-----------------

static_transform_publisher
^^^^^^^^^^^^^^^^^^^^^^^^^^

Publish a static coordinate transform to tf2 using an x/y/z offset in meters and yaw/pitch/roll in radians. (yaw is rotation about Z, pitch is rotation about Y, and roll is rotation about X).

.. code-block:: bash
ros2 run tf2_ros static_transform_publisher [--x X] [--y Y] [--z Z] [--yaw Yaw] [--pitch Pitch] [--roll Roll] --frame_id Frame --child_frame_id Child_Frame
``static_transform_publisher`` can also publish a static coordinate transform to tf2 using an x/y/z offset in meters and quaternion.
Unlike in tf, there is no period argument, and a latched topic is used.

.. code-block:: bash
ros2 run tf2_ros static_transform_publisher [--x X] [--y Y] [--z Z] [--qx QX] [--qy QY] [--qz QZ] [--qw QW] --frame_id Frame --child_frame_id Child_Frame
``static_transform_publisher`` is designed both as a command-line tool for manual use, as well as for use within roslaunch files for setting static transforms. For example:

.. code-block:: yaml
<launch>
<node pkg="tf2_ros" type="static_transform_publisher" name="link1_broadcaster" args="1 0 0 0 0 0 1 link1_parent link1" />
</launch>
29 changes: 24 additions & 5 deletions tf2_ros/docs/source/conf.py → tf2_ros/doc/conf.py
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@

# Add any Sphinx extension module names here, as strings. They can be extensions
# coming with Sphinx (named 'sphinx.ext.*') or your custom ones.
extensions = ['sphinx.ext.autodoc', 'sphinx.ext.doctest', 'sphinx.ext.intersphinx', 'sphinx.ext.imgmath']
extensions = ['sphinx.ext.autodoc', 'sphinx.ext.doctest', 'sphinx.ext.intersphinx', 'sphinx.ext.imgmath', 'sphinx_rtd_theme', 'breathe', 'exhale']

# Add any paths that contain templates here, relative to this directory.
templates_path = ['_templates']
Expand All @@ -45,9 +45,9 @@
# built documents.
#
# The short X.Y version.
version = '0.1'
version = '0.36'
# The full version, including alpha/beta/rc tags.
release = '0.1.0'
release = '0.36.0'

# The language for content autogenerated by Sphinx. Refer to documentation
# for a list of supported languages.
Expand Down Expand Up @@ -91,7 +91,7 @@

# The theme to use for HTML and HTML Help pages. Major themes that come with
# Sphinx are currently 'default' and 'sphinxdoc'.
html_theme = 'default'
html_theme = 'sphinx_rtd_theme'

# Theme options are theme-specific and customize the look and feel of a theme
# further. For a list of options available for each theme, see the
Expand Down Expand Up @@ -193,12 +193,31 @@
# If false, no module index is generated.
#latex_use_modindex = True

# -- Options for manual page output ------------------------------------------

# One entry per manual page. List of tuples
# (source start file, name, description, authors, manual section).
man_pages = [
(master_doc, 'tf2_ros', 'tf2_ros Documentation',
[copyright], 1)
]

# -- Options for Texinfo output ----------------------------------------------

# Grouping the document tree into Texinfo files. List of tuples
# (source start file, target name, title, author,
# dir menu entry, description, category)
texinfo_documents = [
(master_doc, 'tf2_ros', 'tf2_ros Documentation',
copyright, 'tf2_ros', 'ROS 2 ',
'Miscellaneous'),
]

# Example configuration for intersphinx: refer to the Python standard library.
intersphinx_mapping = {
'http://docs.python.org/': None,
'http://docs.opencv.org/3.0-last-rst/': None,
'http://docs.scipy.org/doc/numpy' : None
'http://docs.scipy.org/doc/numpy': None
}

autoclass_content = "both"
Binary file added tf2_ros/doc/images/rqt_tf_tree.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added tf2_ros/doc/images/rviz2_screenshot.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added tf2_ros/doc/images/view_frames.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
79 changes: 79 additions & 0 deletions tf2_ros/doc/index.rst
Original file line number Diff line number Diff line change
@@ -0,0 +1,79 @@
Overview
========

This package contains the ROS 2 bindings for the tf2 library, for both Python and C++.

1.1 Broadcasting Transforms
---------------------------
* :class:`tf2_ros::TransformBroadcaster()` constructor of
(:ref:`exhale_class_classtf2__ros_1_1TransformBroadcaster`)
* :class:`tf2_ros::TransformBroadcaster::sendTransform` to send transforms

Similarly static transforms can be sent by:

* :class:`tf2_ros::StaticTransformBroadcaster()`, constructor of
(:ref:`exhale_class_classtf2__ros_1_1StaticTransformBroadcaster`)
* :class:`tf2_ros::StaticTransformBroadcaster::sendTransform` to send static transforms

1.2 Using Published Transforms
------------------------------
For most purposes using tf2_ros will be done using tf2_ros::Buffer (:ref:`exhale_class_classtf2__ros_1_1Buffer`). It's main public API is defined by tf2_ros::BufferInterface (:ref:`exhale_class_classtf2__ros_1_1BufferInterface`). Typically it will be populated using a tf2_ros::TransformListener (:ref:`exhale_class_classtf2__ros_1_1TransformListener`) which subscribes to the appropriate topics.

* :meth:`tf2_ros::Buffer::transform` is the main method for applying transforms.
* :meth:`canTransform` allows to know if a transform is available
* :meth:`lookupTransform` is a lower level method which returns the transform between two coordinate frames. This method is the core functionality of the tf2 library.
* :meth:`getFrames` is a service method providing the frames in the graph as a yaml tree

1.3 Filtering Transforms
------------------------

``tf2_ros`` provides a feature which allows to pass only the messages once there is transform data available. This follows the pattern from the ``message_filters`` package. Here is a brief list of functions that the user is most likely to use.

* :class:`tf2_ros::MessageFilter()` constructor of (:ref:`exhale_class_classtf2__ros_1_1MessageFilter`)
* :meth:`connectInput()` allows to connect filters together

* :meth:`setTargetFrame()` set the frame you want to be able to transform to before getting a message callback

* :meth:`setTargetFrames()` set the frames you want to be able to transform to before getting a message callback

* :meth:`setTolerance()` specifies the time tolerance for the transform data

* :meth:`clear()` flushes the message queue

* :meth:`setQueueSize()` creates a maximum number of messages in the queue

1.4 Exceptions
--------------

Here is the list of exceptions that can be thrown by ``tf2_ros`` and are inherited from tf2.

* tf2::ConnectivityException

* tf2::LookupException

* tf2::ExtrapolationException

* tf2::InvalidArgumentException

* tf2::TimeoutException

* tf2::TransformException

Tree
====

.. toctree::
:maxdepth: 2

self
cli_tools
tf2_ros2
C++ API Docs <generated/index>
Python Modules <modules>


Indices and tables
==================

* :ref:`genindex`
* :ref:`search`
2 changes: 1 addition & 1 deletion tf2_ros/docs/mainpage.dox → tf2_ros/doc/mainpage.dox
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ List of exceptions thrown in this library:
- tf2::TimeoutException
- tf2::TransformException

For more information, see the tf2 tutorials: http://wiki.ros.org/tf2/Tutorials
For more information, see the tf2 tutorials: https://docs.ros.org/en/rolling/Tutorials/Intermediate/Tf2/Tf2-Main.html#

Or, get an <A HREF="http://wiki.ros.org/tf2/Tutorials/Migration/DataConversions">overview</A> of data type conversion methods in geometry_experimental packages.
*/
File renamed without changes.
10 changes: 5 additions & 5 deletions tf2_ros/docs/source/tf2_ros.rst → tf2_ros/doc/tf2_ros2.rst
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
tf_ros2 Python API
tf2_ros Python API
==================

Exceptions
Expand All @@ -14,7 +14,7 @@ Exceptions
# do some tf2 work
except tf2.TransformException:
print "some tf2 exception happened"


.. exception:: tf2.ConnectivityException

Expand All @@ -27,8 +27,8 @@ Exceptions
Raised when a tf method has attempted to access a frame, but
the frame is not in the graph.
The most common reason for this is that the frame is not
being published, or a parent frame was not set correctly
causing the tree to be broken.
being published, or a parent frame was not set correctly
causing the tree to be broken.

.. exception:: tf2.ExtrapolationException

Expand All @@ -39,7 +39,7 @@ Exceptions
.. exception:: tf2.InvalidArgumentException

subclass of :exc:`TransformException`.
Raised when the arguments to the method are called improperly formed. An example of why this might be raised is if an argument is nan.
Raised when the arguments to the method are called improperly formed. An example of why this might be raised is if an argument is nan.

.. autoexception:: tf2_ros.buffer_interface.TypeException

Expand Down
48 changes: 0 additions & 48 deletions tf2_ros/docs/source/index.rst

This file was deleted.

1 change: 1 addition & 0 deletions tf2_ros/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -34,5 +34,6 @@

<export>
<build_type>ament_cmake</build_type>
<rosdoc2>rosdoc2.yaml</rosdoc2>
</export>
</package>
Loading

0 comments on commit c9ca2ca

Please sign in to comment.