Public Types | Public Member Functions | Private Types | Private Member Functions | Private Attributes
tf::MessageFilterJointState Class Reference

#include <effort_display.h>

Inheritance diagram for tf::MessageFilterJointState:
Inheritance graph
[legend]

List of all members.

Public Types

typedef boost::function< void(const
MConstPtr
&, FilterFailureReason)> 
FailureCallback
typedef boost::signal< void(const
MConstPtr
&, FilterFailureReason)> 
FailureSignal
typedef boost::shared_ptr< M
const > 
MConstPtr
typedef ros::MessageEvent< M
const > 
MEvent

Public Member Functions

void add (const MEvent &evt)
void add (const MConstPtr &message)
 Manually add a message into this filter.
void clear ()
 Clear any messages currently in the queue.
template<class F >
void connectInput (F &f)
 Connect this filter's input to another filter's output. If this filter is already connected, disconnects first.
virtual uint32_t getQueueSize ()
std::string getTargetFramesString ()
 Get the target frames as a string for debugging.
 MessageFilterJointState (Transformer &tf, const std::string &target_frame, uint32_t queue_size, ros::NodeHandle nh=ros::NodeHandle(), ros::Duration max_rate=ros::Duration(0.01))
 Constructor.
template<class F >
 MessageFilterJointState (F &f, Transformer &tf, const std::string &target_frame, uint32_t queue_size, ros::NodeHandle nh=ros::NodeHandle(), ros::Duration max_rate=ros::Duration(0.01))
 Constructor.
message_filters::Connection registerFailureCallback (const FailureCallback &callback)
 Register a callback to be called when a message is about to be dropped.
 ROS_STATIC_ASSERT (ros::message_traits::HasHeader< M >::value)
virtual void setQueueSize (uint32_t new_queue_size)
void setTargetFrame (const std::string &target_frame)
 Set the frame you need to be able to transform to before getting a message callback.
void setTargetFrames (const std::vector< std::string > &target_frames)
 Set the frames you need to be able to transform to before getting a message callback.
void setTolerance (const ros::Duration &tolerance)
 Set the required tolerance for the notifier to return true.
 ~MessageFilterJointState ()
 Destructor.

Private Types

typedef std::list< MEventL_Event
typedef sensor_msgs::JointState M

Private Member Functions

void checkFailures ()
void disconnectFailure (const message_filters::Connection &c)
void incomingMessage (const ros::MessageEvent< M const > &evt)
 Callback that happens when we receive a message on the message topic.
void init ()
void maxRateTimerCallback (const ros::TimerEvent &)
void signalFailure (const MEvent &evt, FilterFailureReason reason)
bool testMessage (const MEvent &evt)
void testMessages ()
void transformsChanged ()

Private Attributes

uint64_t dropped_message_count_
uint64_t failed_out_the_back_count_
uint64_t failed_transform_count_
FailureSignal failure_signal_
boost::mutex failure_signal_mutex_
uint64_t incoming_message_count_
std::string last_out_the_back_frame_
ros::Time last_out_the_back_stamp_
ros::Duration max_rate_
ros::Timer max_rate_timer_
message_filters::Connection message_connection_
uint32_t message_count_
 The number of messages in the list. Used because messages_.size() has linear cost.
L_Event messages_
 The message list.
boost::mutex messages_mutex_
 The mutex used for locking message list operations.
bool new_messages_
 Used to skip waiting on new_data_ if new messages have come in while calling back.
volatile bool new_transforms_
 Used to skip waiting on new_data_ if new transforms have come in while calling back or transforming data.
ros::Time next_failure_warning_
ros::NodeHandle nh_
 The node used to subscribe to the topic.
uint32_t queue_size_
 The maximum number of messages we queue up.
uint64_t successful_transform_count_
std::vector< std::string > target_frames_
 The frames we need to be able to transform to before a message is ready.
std::string target_frames_string_
boost::mutex target_frames_string_mutex_
Transformertf_
 The Transformer used to determine if transformation data is available.
boost::signals::connection tf_connection_
ros::Duration time_tolerance_
 Provide additional tolerance on time for messages which are stamped but can have associated duration.
uint64_t transform_message_count_
bool warned_about_empty_frame_id_
bool warned_about_unresolved_name_

Detailed Description

Definition at line 39 of file effort_display.h.


Member Typedef Documentation

Reimplemented from tf::MessageFilter< sensor_msgs::JointState >.

Definition at line 45 of file effort_display.h.

Reimplemented from tf::MessageFilter< sensor_msgs::JointState >.

Definition at line 46 of file effort_display.h.

typedef std::list<MEvent> tf::MessageFilterJointState::L_Event [private]

Reimplemented from tf::MessageFilter< sensor_msgs::JointState >.

Definition at line 268 of file effort_display.h.

typedef sensor_msgs::JointState tf::MessageFilterJointState::M [private]

Definition at line 41 of file effort_display.h.

typedef boost::shared_ptr<M const> tf::MessageFilterJointState::MConstPtr

Reimplemented from tf::MessageFilter< sensor_msgs::JointState >.

Definition at line 43 of file effort_display.h.

Reimplemented from tf::MessageFilter< sensor_msgs::JointState >.

Definition at line 44 of file effort_display.h.


Constructor & Destructor Documentation

tf::MessageFilterJointState::MessageFilterJointState ( Transformer tf,
const std::string &  target_frame,
uint32_t  queue_size,
ros::NodeHandle  nh = ros::NodeHandle(),
ros::Duration  max_rate = ros::Duration(0.01) 
) [inline]

Constructor.

Parameters:
tfThe tf::Transformer this filter should use
target_frameThe frame this filter should attempt to transform to. To use multiple frames, pass an empty string here and use the setTargetFrames() function.
queue_sizeThe number of messages to queue up before throwing away old ones. 0 means infinite (dangerous).
nhThe NodeHandle to use for any necessary operations
max_rateThe maximum rate to check for newly transformable messages

Definition at line 60 of file effort_display.h.

template<class F >
tf::MessageFilterJointState::MessageFilterJointState ( F &  f,
Transformer tf,
const std::string &  target_frame,
uint32_t  queue_size,
ros::NodeHandle  nh = ros::NodeHandle(),
ros::Duration  max_rate = ros::Duration(0.01) 
) [inline]

Constructor.

Parameters:
fThe filter to connect this filter's input to. Often will be a message_filters::Subscriber.
tfThe tf::Transformer this filter should use
target_frameThe frame this filter should attempt to transform to. To use multiple frames, pass an empty string here and use the setTargetFrames() function.
queue_sizeThe number of messages to queue up before throwing away old ones. 0 means infinite (dangerous).
nhThe NodeHandle to use for any necessary operations
max_rateThe maximum rate to check for newly transformable messages

Definition at line 83 of file effort_display.h.

Destructor.

Definition at line 110 of file effort_display.h.


Member Function Documentation

void tf::MessageFilterJointState::add ( const MEvent evt) [inline]

Reimplemented from tf::MessageFilter< sensor_msgs::JointState >.

Definition at line 185 of file effort_display.h.

void tf::MessageFilterJointState::add ( const MConstPtr message) [inline]

Manually add a message into this filter.

Note:
If the message (or any other messages in the queue) are immediately transformable this will immediately call through to the output callback, possibly multiple times

Reimplemented from tf::MessageFilter< sensor_msgs::JointState >.

Definition at line 220 of file effort_display.h.

void tf::MessageFilterJointState::checkFailures ( ) [inline, private]

Reimplemented from tf::MessageFilter< sensor_msgs::JointState >.

Definition at line 414 of file effort_display.h.

void tf::MessageFilterJointState::clear ( ) [inline, virtual]

Clear any messages currently in the queue.

Reimplemented from tf::MessageFilter< sensor_msgs::JointState >.

Definition at line 172 of file effort_display.h.

template<class F >
void tf::MessageFilterJointState::connectInput ( F &  f) [inline]

Connect this filter's input to another filter's output. If this filter is already connected, disconnects first.

Reimplemented from tf::MessageFilter< sensor_msgs::JointState >.

Definition at line 101 of file effort_display.h.

Reimplemented from tf::MessageFilter< sensor_msgs::JointState >.

Definition at line 442 of file effort_display.h.

virtual uint32_t tf::MessageFilterJointState::getQueueSize ( ) [inline, virtual]

Reimplemented from tf::MessageFilter< sensor_msgs::JointState >.

Definition at line 242 of file effort_display.h.

Get the target frames as a string for debugging.

Reimplemented from tf::MessageFilter< sensor_msgs::JointState >.

Definition at line 155 of file effort_display.h.

void tf::MessageFilterJointState::incomingMessage ( const ros::MessageEvent< M const > &  evt) [inline, private]

Callback that happens when we receive a message on the message topic.

Reimplemented from tf::MessageFilter< sensor_msgs::JointState >.

Definition at line 402 of file effort_display.h.

void tf::MessageFilterJointState::init ( ) [inline, private]

Reimplemented from tf::MessageFilter< sensor_msgs::JointState >.

Definition at line 249 of file effort_display.h.

Reimplemented from tf::MessageFilter< sensor_msgs::JointState >.

Definition at line 387 of file effort_display.h.

Register a callback to be called when a message is about to be dropped.

Parameters:
callbackThe callback to call

Reimplemented from tf::MessageFilter< sensor_msgs::JointState >.

Definition at line 231 of file effort_display.h.

virtual void tf::MessageFilterJointState::setQueueSize ( uint32_t  new_queue_size) [inline, virtual]

Reimplemented from tf::MessageFilter< sensor_msgs::JointState >.

Definition at line 237 of file effort_display.h.

void tf::MessageFilterJointState::setTargetFrame ( const std::string &  target_frame) [inline, virtual]

Set the frame you need to be able to transform to before getting a message callback.

Reimplemented from tf::MessageFilter< sensor_msgs::JointState >.

Definition at line 127 of file effort_display.h.

void tf::MessageFilterJointState::setTargetFrames ( const std::vector< std::string > &  target_frames) [inline, virtual]

Set the frames you need to be able to transform to before getting a message callback.

Reimplemented from tf::MessageFilter< sensor_msgs::JointState >.

Definition at line 137 of file effort_display.h.

void tf::MessageFilterJointState::setTolerance ( const ros::Duration tolerance) [inline, virtual]

Set the required tolerance for the notifier to return true.

Reimplemented from tf::MessageFilter< sensor_msgs::JointState >.

Definition at line 164 of file effort_display.h.

void tf::MessageFilterJointState::signalFailure ( const MEvent evt,
FilterFailureReason  reason 
) [inline, private]

Reimplemented from tf::MessageFilter< sensor_msgs::JointState >.

Definition at line 448 of file effort_display.h.

bool tf::MessageFilterJointState::testMessage ( const MEvent evt) [inline, private]
Todo:
combine getLatestCommonTime call with the canTransform call

Reimplemented from tf::MessageFilter< sensor_msgs::JointState >.

Definition at line 270 of file effort_display.h.

void tf::MessageFilterJointState::testMessages ( ) [inline, private]

Reimplemented from tf::MessageFilter< sensor_msgs::JointState >.

Definition at line 361 of file effort_display.h.

Reimplemented from tf::MessageFilter< sensor_msgs::JointState >.

Definition at line 407 of file effort_display.h.


Member Data Documentation

Reimplemented from tf::MessageFilter< sensor_msgs::JointState >.

Definition at line 478 of file effort_display.h.

Reimplemented from tf::MessageFilter< sensor_msgs::JointState >.

Definition at line 475 of file effort_display.h.

Reimplemented from tf::MessageFilter< sensor_msgs::JointState >.

Definition at line 474 of file effort_display.h.

Reimplemented from tf::MessageFilter< sensor_msgs::JointState >.

Definition at line 490 of file effort_display.h.

Reimplemented from tf::MessageFilter< sensor_msgs::JointState >.

Definition at line 491 of file effort_display.h.

Reimplemented from tf::MessageFilter< sensor_msgs::JointState >.

Definition at line 477 of file effort_display.h.

Reimplemented from tf::MessageFilter< sensor_msgs::JointState >.

Definition at line 481 of file effort_display.h.

Reimplemented from tf::MessageFilter< sensor_msgs::JointState >.

Definition at line 480 of file effort_display.h.

Reimplemented from tf::MessageFilter< sensor_msgs::JointState >.

Definition at line 456 of file effort_display.h.

Reimplemented from tf::MessageFilter< sensor_msgs::JointState >.

Definition at line 457 of file effort_display.h.

Reimplemented from tf::MessageFilter< sensor_msgs::JointState >.

Definition at line 488 of file effort_display.h.

The number of messages in the list. Used because messages_.size() has linear cost.

Reimplemented from tf::MessageFilter< sensor_msgs::JointState >.

Definition at line 464 of file effort_display.h.

The message list.

Reimplemented from tf::MessageFilter< sensor_msgs::JointState >.

Definition at line 463 of file effort_display.h.

The mutex used for locking message list operations.

Reimplemented from tf::MessageFilter< sensor_msgs::JointState >.

Definition at line 465 of file effort_display.h.

Used to skip waiting on new_data_ if new messages have come in while calling back.

Reimplemented from tf::MessageFilter< sensor_msgs::JointState >.

Definition at line 467 of file effort_display.h.

Used to skip waiting on new_data_ if new transforms have come in while calling back or transforming data.

Reimplemented from tf::MessageFilter< sensor_msgs::JointState >.

Definition at line 468 of file effort_display.h.

Reimplemented from tf::MessageFilter< sensor_msgs::JointState >.

Definition at line 483 of file effort_display.h.

The node used to subscribe to the topic.

Reimplemented from tf::MessageFilter< sensor_msgs::JointState >.

Definition at line 455 of file effort_display.h.

The maximum number of messages we queue up.

Reimplemented from tf::MessageFilter< sensor_msgs::JointState >.

Definition at line 461 of file effort_display.h.

Reimplemented from tf::MessageFilter< sensor_msgs::JointState >.

Definition at line 473 of file effort_display.h.

std::vector<std::string> tf::MessageFilterJointState::target_frames_ [private]

The frames we need to be able to transform to before a message is ready.

Reimplemented from tf::MessageFilter< sensor_msgs::JointState >.

Definition at line 458 of file effort_display.h.

Reimplemented from tf::MessageFilter< sensor_msgs::JointState >.

Definition at line 459 of file effort_display.h.

Reimplemented from tf::MessageFilter< sensor_msgs::JointState >.

Definition at line 460 of file effort_display.h.

The Transformer used to determine if transformation data is available.

Reimplemented from tf::MessageFilter< sensor_msgs::JointState >.

Definition at line 454 of file effort_display.h.

boost::signals::connection tf::MessageFilterJointState::tf_connection_ [private]

Reimplemented from tf::MessageFilter< sensor_msgs::JointState >.

Definition at line 487 of file effort_display.h.

Provide additional tolerance on time for messages which are stamped but can have associated duration.

Reimplemented from tf::MessageFilter< sensor_msgs::JointState >.

Definition at line 485 of file effort_display.h.

Reimplemented from tf::MessageFilter< sensor_msgs::JointState >.

Definition at line 476 of file effort_display.h.

Reimplemented from tf::MessageFilter< sensor_msgs::JointState >.

Definition at line 471 of file effort_display.h.

Reimplemented from tf::MessageFilter< sensor_msgs::JointState >.

Definition at line 470 of file effort_display.h.


The documentation for this class was generated from the following file:


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Mon Oct 6 2014 07:26:37