Namespaces | Classes | Typedefs | Functions | Variables
tf2_ros Namespace Reference

Namespaces

namespace  filter_failure_reasons

Classes

class  Buffer
class  BufferClient
class  BufferInterface
class  BufferServer
class  MessageFilter
 Follows the patterns set by the message_filters package to implement a filter which only passes messages through once there is transform data available. More...
class  MessageFilterBase
class  StaticTransformBroadcaster
 This class provides an easy way to publish coordinate frame transform information. It will handle all the messaging and stuffing of messages. And the function prototypes lay out all the necessary data needed for each message. More...
class  TransformBroadcaster
 This class provides an easy way to publish coordinate frame transform information. It will handle all the messaging and stuffing of messages. And the function prototypes lay out all the necessary data needed for each message. More...
class  TransformListener

Typedefs

typedef
filter_failure_reasons::FilterFailureReason 
FilterFailureReason

Functions

ros::Time now_fallback_to_wall ()
void sleep_fallback_to_wall (const ros::Duration &d)

Variables

static const std::string threading_error = "Do not call canTransform or lookupTransform with a timeout unless you are using another thread for populating data. Without a dedicated thread it will always timeout. If you have a seperate thread servicing tf messages, call setUsingDedicatedThread(true) on your Buffer instance."

Detailed Description

Author:
Wim Meeussen
Tully Foote

Typedef Documentation

Definition at line 74 of file message_filter.h.


Function Documentation

This is a workaround for the case that we're running inside of rospy and ros::Time is not initialized inside the c++ instance. This makes the system fall back to Wall time if not initialized.

Definition at line 72 of file buffer.cpp.

This is a workaround for the case that we're running inside of rospy and ros::Time is not initialized inside the c++ instance. This makes the system fall back to Wall time if not initialized. https://github.com/ros/geometry/issues/30

Definition at line 90 of file buffer.cpp.


Variable Documentation

const std::string tf2_ros::threading_error = "Do not call canTransform or lookupTransform with a timeout unless you are using another thread for populating data. Without a dedicated thread it will always timeout. If you have a seperate thread servicing tf messages, call setUsingDedicatedThread(true) on your Buffer instance." [static]

Definition at line 134 of file buffer.h.



tf2_ros
Author(s): Eitan Marder-Eppstein, Wim Meeussen
autogenerated on Thu Aug 27 2015 13:10:05