## repository: unknown
<<PackageHeader(tf2_ros)>> <<TOC(4)>>

== Documentation ==
This package provides roscpp and rospy bindings for tf2. Here is a list of the common method that should be used when interacting with tf2 function within ROS.

=== Broadcasting Transforms ===
$ROS_DISTRO

 * `tf2_ros::TransformBroadcaster()`, constructor
 * `tf2_ros::TransformBroadcaster::sendTransform` to send transforms
Please refer to the [[http://docs.ros.org/latest/api/tf2_ros/html/c++/classtf2__ros_1_1TransformBroadcaster.html| C++ API]] or [[ http://docs.ros.org/latest/api/tf2_ros/html/python/tf2_ros.html#transformbroadcaster | Python API]]

Similarly static transforms can be sent by:
 * `tf2_ros::StaticTransformBroadcaster()`, constructor,
 * `tf2_ros::StaticTransformBroadcaster::sendTransform` to send static transforms
Please refer to the [[http://docs.ros.org/latest/api/tf2_ros/html/c++/classtf2__ros_1_1StaticTransformBroadcaster.html| C++ API]] or [[ http://docs.ros.org/latest/api/tf2_ros/html/python/tf2_ros.html#statictransformbroadcaster| Python API]]

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

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

Please refer to the [[http://docs.ros.org/latest/api/tf2_ros/html/c++/classtf2__ros_1_1TransformListener.html | C++ API]] or [[ http://docs.ros.org/latest/api/tf2_ros/html/python/tf2_ros.html#transformlistener| Python Api]]

=== 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.
 * `tf2_ros::MessageFilter()`, constructor
 * `connectInput()` allows to connect filters together
 * `setTargetFrame()` set the frame you want to be able to transform to before getting a message callback
 * `setTargetFrames()` set the frames you want to be able to transform to before getting a message callback
 * `setTolerance()` specifies the time tolerance for the transform data
 * `clear` flushes the message queue
 * `setQueueSize()`

Please refer to the [[http://docs.ros.org/latest/api/tf2_ros/html/c++/classtf2__ros_1_1MessageFilter.html | C++ API]] or [[ | Python Api]]

=== 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`

For more information see [[http://docs.ros.org/latest/api/tf2/html/exceptions_8h.html| C++ exceptions]] or [[http://docs.ros.org/latest/api/tf2_ros/html/python/tf2_ros.html#tf2.TransformException |Python Exceptions]]

=== Tools ===
==== static_transform_publisher ====
##statictranformpubstart
`static_transform_publisher x y z yaw pitch roll frame_id child_frame_id`

 . 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).

`static_transform_publisher x y z qx qy qz qw frame_id child_frame_id`

 . 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.

`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:

{{{#!xml
<launch>
<node pkg="tf2_ros" type="static_transform_publisher" name="link1_broadcaster" args="1 0 0 0 0 0 1 link1_parent link1" />
</launch>
}}}
##statictranformpubend

## AUTOGENERATED DON'T DELETE
## CategoryPackage