Public Types | Public Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
tf::MessageFilterJointState Class Reference

#include <effort_display.h>

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

Public Types

typedef boost::function< void(const MConstPtr &, FilterFailureReason)> FailureCallback
 
typedef boost::signals2::signal< void(const MConstPtr &, FilterFailureReason)> FailureSignal
 
typedef boost::shared_ptr< M const > MConstPtr
 
typedef ros::MessageEvent< M const > MEvent
 
- Public Types inherited from tf::MessageFilter< sensor_msgs::JointState >
typedef boost::function< void(const MConstPtr &, FilterFailureReason)> FailureCallback
 
typedef boost::signals2::signal< void(const MConstPtr &, FilterFailureReason)> FailureSignal
 
typedef boost::shared_ptr< sensor_msgs::JointStateconst > MConstPtr
 
typedef ros::MessageEvent< sensor_msgs::JointStateconst > MEvent
 
- Public Types inherited from message_filters::SimpleFilter< M >
typedef boost::function< void(const MConstPtr &)> Callback
 
typedef boost::function< void(const EventType &)> EventCallback
 
typedef ros::MessageEvent< M const > EventType
 
typedef boost::shared_ptr< M const > MConstPtr
 

Public Member Functions

void add (const MEvent &evt)
 
void add (const MConstPtr &message)
 Manually add a message into this filter. More...
 
void clear ()
 Clear any messages currently in the queue. More...
 
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. More...
 
virtual uint32_t getQueueSize ()
 
std::string getTargetFramesString ()
 Get the target frames as a string for debugging. More...
 
 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. More...
 
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. More...
 
message_filters::Connection registerFailureCallback (const FailureCallback &callback)
 Register a callback to be called when a message is about to be dropped. More...
 
 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. More...
 
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. More...
 
void setTolerance (const ros::Duration &tolerance)
 Set the required tolerance for the notifier to return true. More...
 
 ~MessageFilterJointState ()
 Destructor. More...
 
- Public Member Functions inherited from tf::MessageFilter< sensor_msgs::JointState >
void add (const MEvent &evt)
 
void add (const MConstPtr &message)
 
void clear ()
 
void connectInput (F &f)
 
std::string getTargetFramesString ()
 
 MessageFilter (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))
 
 MessageFilter (Transformer &tf, const std::string &target_frame, uint32_t queue_size, ros::NodeHandle nh=ros::NodeHandle(), ros::Duration max_rate=ros::Duration(0.01))
 
message_filters::Connection registerFailureCallback (const FailureCallback &callback)
 
void setTargetFrame (const std::string &target_frame)
 
void setTargetFrames (const std::vector< std::string > &target_frames)
 
void setTolerance (const ros::Duration &tolerance)
 
 ~MessageFilter ()
 
- Public Member Functions inherited from tf::MessageFilterBase
virtual ~MessageFilterBase ()
 
- Public Member Functions inherited from message_filters::SimpleFilter< M >
const std::string & getName ()
 
Connection registerCallback (const C &callback)
 
Connection registerCallback (void(T::*callback)(P), T *t)
 
Connection registerCallback (void(*callback)(P))
 
Connection registerCallback (const boost::function< void(P)> &callback)
 
void setName (const std::string &name)
 

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. More...
 
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. More...
 
L_Event messages_
 The message list. More...
 
boost::mutex messages_mutex_
 The mutex used for locking message list operations. More...
 
bool new_messages_
 Used to skip waiting on new_data_ if new messages have come in while calling back. More...
 
volatile bool new_transforms_
 Used to skip waiting on new_data_ if new transforms have come in while calling back or transforming data. More...
 
ros::Time next_failure_warning_
 
ros::NodeHandle nh_
 The node used to subscribe to the topic. More...
 
uint32_t queue_size_
 The maximum number of messages we queue up. More...
 
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. More...
 
std::string target_frames_string_
 
boost::mutex target_frames_string_mutex_
 
Transformertf_
 The Transformer used to determine if transformation data is available. More...
 
boost::signals2::connection tf_connection_
 
ros::Duration time_tolerance_
 Provide additional tolerance on time for messages which are stamped but can have associated duration. More...
 
uint64_t transform_message_count_
 
bool warned_about_empty_frame_id_
 
bool warned_about_unresolved_name_
 

Additional Inherited Members

- Protected Member Functions inherited from message_filters::SimpleFilter< M >
void signalMessage (const MConstPtr &msg)
 
void signalMessage (const ros::MessageEvent< M const > &event)
 

Detailed Description

Definition at line 47 of file effort_display.h.

Member Typedef Documentation

Definition at line 53 of file effort_display.h.

typedef boost::signals2::signal<void(const MConstPtr&, FilterFailureReason)> tf::MessageFilterJointState::FailureSignal

Definition at line 57 of file effort_display.h.

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

Definition at line 280 of file effort_display.h.

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

Definition at line 49 of file effort_display.h.

Definition at line 51 of file effort_display.h.

Definition at line 52 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 72 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 95 of file effort_display.h.

tf::MessageFilterJointState::~MessageFilterJointState ( )
inline

Destructor.

Definition at line 122 of file effort_display.h.

Member Function Documentation

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

Definition at line 197 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

Definition at line 232 of file effort_display.h.

void tf::MessageFilterJointState::checkFailures ( )
inlineprivate

Definition at line 426 of file effort_display.h.

void tf::MessageFilterJointState::clear ( )
inlinevirtual

Clear any messages currently in the queue.

Implements tf::MessageFilterBase.

Definition at line 184 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.

Definition at line 113 of file effort_display.h.

void tf::MessageFilterJointState::disconnectFailure ( const message_filters::Connection c)
inlineprivate

Definition at line 454 of file effort_display.h.

virtual uint32_t tf::MessageFilterJointState::getQueueSize ( )
inlinevirtual

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

Definition at line 254 of file effort_display.h.

std::string tf::MessageFilterJointState::getTargetFramesString ( )
inline

Get the target frames as a string for debugging.

Definition at line 167 of file effort_display.h.

void tf::MessageFilterJointState::incomingMessage ( const ros::MessageEvent< M const > &  evt)
inlineprivate

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

Definition at line 414 of file effort_display.h.

void tf::MessageFilterJointState::init ( )
inlineprivate

Definition at line 261 of file effort_display.h.

void tf::MessageFilterJointState::maxRateTimerCallback ( const ros::TimerEvent )
inlineprivate

Definition at line 399 of file effort_display.h.

message_filters::Connection tf::MessageFilterJointState::registerFailureCallback ( const FailureCallback callback)
inline

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

Parameters
callbackThe callback to call

Definition at line 243 of file effort_display.h.

tf::MessageFilterJointState::ROS_STATIC_ASSERT ( ros::message_traits::HasHeader< M >::value  )
virtual void tf::MessageFilterJointState::setQueueSize ( uint32_t  new_queue_size)
inlinevirtual

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

Definition at line 249 of file effort_display.h.

void tf::MessageFilterJointState::setTargetFrame ( const std::string &  target_frame)
inlinevirtual

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

Implements tf::MessageFilterBase.

Definition at line 139 of file effort_display.h.

void tf::MessageFilterJointState::setTargetFrames ( const std::vector< std::string > &  target_frames)
inlinevirtual

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

Implements tf::MessageFilterBase.

Definition at line 149 of file effort_display.h.

void tf::MessageFilterJointState::setTolerance ( const ros::Duration tolerance)
inlinevirtual

Set the required tolerance for the notifier to return true.

Implements tf::MessageFilterBase.

Definition at line 176 of file effort_display.h.

void tf::MessageFilterJointState::signalFailure ( const MEvent evt,
FilterFailureReason  reason 
)
inlineprivate

Definition at line 460 of file effort_display.h.

bool tf::MessageFilterJointState::testMessage ( const MEvent evt)
inlineprivate
Todo:
combine getLatestCommonTime call with the canTransform call

Definition at line 282 of file effort_display.h.

void tf::MessageFilterJointState::testMessages ( )
inlineprivate

Definition at line 373 of file effort_display.h.

void tf::MessageFilterJointState::transformsChanged ( )
inlineprivate

Definition at line 419 of file effort_display.h.

Member Data Documentation

uint64_t tf::MessageFilterJointState::dropped_message_count_
private

Definition at line 490 of file effort_display.h.

uint64_t tf::MessageFilterJointState::failed_out_the_back_count_
private

Definition at line 487 of file effort_display.h.

uint64_t tf::MessageFilterJointState::failed_transform_count_
private

Definition at line 486 of file effort_display.h.

FailureSignal tf::MessageFilterJointState::failure_signal_
private

Definition at line 506 of file effort_display.h.

boost::mutex tf::MessageFilterJointState::failure_signal_mutex_
private

Definition at line 507 of file effort_display.h.

uint64_t tf::MessageFilterJointState::incoming_message_count_
private

Definition at line 489 of file effort_display.h.

std::string tf::MessageFilterJointState::last_out_the_back_frame_
private

Definition at line 493 of file effort_display.h.

ros::Time tf::MessageFilterJointState::last_out_the_back_stamp_
private

Definition at line 492 of file effort_display.h.

ros::Duration tf::MessageFilterJointState::max_rate_
private

Definition at line 468 of file effort_display.h.

ros::Timer tf::MessageFilterJointState::max_rate_timer_
private

Definition at line 469 of file effort_display.h.

message_filters::Connection tf::MessageFilterJointState::message_connection_
private

Definition at line 504 of file effort_display.h.

uint32_t tf::MessageFilterJointState::message_count_
private

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

Definition at line 476 of file effort_display.h.

L_Event tf::MessageFilterJointState::messages_
private

The message list.

Definition at line 475 of file effort_display.h.

boost::mutex tf::MessageFilterJointState::messages_mutex_
private

The mutex used for locking message list operations.

Definition at line 477 of file effort_display.h.

bool tf::MessageFilterJointState::new_messages_
private

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

Definition at line 479 of file effort_display.h.

volatile bool tf::MessageFilterJointState::new_transforms_
private

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

Definition at line 480 of file effort_display.h.

ros::Time tf::MessageFilterJointState::next_failure_warning_
private

Definition at line 495 of file effort_display.h.

ros::NodeHandle tf::MessageFilterJointState::nh_
private

The node used to subscribe to the topic.

Definition at line 467 of file effort_display.h.

uint32_t tf::MessageFilterJointState::queue_size_
private

The maximum number of messages we queue up.

Definition at line 473 of file effort_display.h.

uint64_t tf::MessageFilterJointState::successful_transform_count_
private

Definition at line 485 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.

Definition at line 470 of file effort_display.h.

std::string tf::MessageFilterJointState::target_frames_string_
private

Definition at line 471 of file effort_display.h.

boost::mutex tf::MessageFilterJointState::target_frames_string_mutex_
private

Definition at line 472 of file effort_display.h.

Transformer& tf::MessageFilterJointState::tf_
private

The Transformer used to determine if transformation data is available.

Definition at line 466 of file effort_display.h.

boost::signals2::connection tf::MessageFilterJointState::tf_connection_
private

Definition at line 502 of file effort_display.h.

ros::Duration tf::MessageFilterJointState::time_tolerance_
private

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

Definition at line 497 of file effort_display.h.

uint64_t tf::MessageFilterJointState::transform_message_count_
private

Definition at line 488 of file effort_display.h.

bool tf::MessageFilterJointState::warned_about_empty_frame_id_
private

Definition at line 483 of file effort_display.h.

bool tf::MessageFilterJointState::warned_about_unresolved_name_
private

Definition at line 482 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 Wed Aug 28 2019 04:01:54