Classes | Namespaces | Defines | Typedefs | Enumerations
message_filter.h File Reference
#include <tf2/buffer_core.h>
#include <string>
#include <list>
#include <vector>
#include <boost/function.hpp>
#include <boost/bind.hpp>
#include <boost/shared_ptr.hpp>
#include <boost/thread.hpp>
#include <message_filters/connection.h>
#include <message_filters/simple_filter.h>
#include <ros/node_handle.h>
#include <ros/callback_queue_interface.h>
#include <ros/init.h>
Include dependency graph for message_filter.h:

Go to the source code of this file.

Classes

struct  tf2_ros::MessageFilter< M >::CBQueueCallback
class  tf2_ros::MessageFilter< M >
 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  tf2_ros::MessageFilterBase
struct  tf2_ros::MessageFilter< M >::MessageInfo

Namespaces

namespace  tf2_ros
namespace  tf2_ros::filter_failure_reasons

Defines

#define TF2_ROS_MESSAGEFILTER_DEBUG(fmt,...)   ROS_DEBUG_NAMED("message_filter", std::string(std::string("MessageFilter [target=%s]: ") + std::string(fmt)).c_str(), getTargetFramesString().c_str(), __VA_ARGS__)
#define TF2_ROS_MESSAGEFILTER_WARN(fmt,...)   ROS_WARN_NAMED("message_filter", std::string(std::string("MessageFilter [target=%s]: ") + std::string(fmt)).c_str(), getTargetFramesString().c_str(), __VA_ARGS__)

Typedefs

typedef
filter_failure_reasons::FilterFailureReason 
tf2_ros::FilterFailureReason

Enumerations

enum  tf2_ros::filter_failure_reasons::FilterFailureReason { tf2_ros::filter_failure_reasons::Unknown, tf2_ros::filter_failure_reasons::OutTheBack, tf2_ros::filter_failure_reasons::EmptyFrameID }

Define Documentation

#define TF2_ROS_MESSAGEFILTER_DEBUG (   fmt,
  ... 
)    ROS_DEBUG_NAMED("message_filter", std::string(std::string("MessageFilter [target=%s]: ") + std::string(fmt)).c_str(), getTargetFramesString().c_str(), __VA_ARGS__)
Author:
Josh Faust

Definition at line 52 of file message_filter.h.

#define TF2_ROS_MESSAGEFILTER_WARN (   fmt,
  ... 
)    ROS_WARN_NAMED("message_filter", std::string(std::string("MessageFilter [target=%s]: ") + std::string(fmt)).c_str(), getTargetFramesString().c_str(), __VA_ARGS__)

Definition at line 55 of file message_filter.h.



tf2_ros
Author(s): Eitan Marder-Eppstein, Wim Meeussen
autogenerated on Thu Jun 6 2019 20:23:00