#include <effort_display.h>
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 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 () |
Private Types | |
typedef std::list< MEvent > | L_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_ |
Transformer & | tf_ |
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 |
Definition at line 47 of file effort_display.h.
typedef boost::function<void(const MConstPtr&, FilterFailureReason)> tf::MessageFilterJointState::FailureCallback |
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.
|
private |
Definition at line 280 of file effort_display.h.
|
private |
Definition at line 49 of file effort_display.h.
typedef boost::shared_ptr<M const> tf::MessageFilterJointState::MConstPtr |
Definition at line 51 of file effort_display.h.
typedef ros::MessageEvent<M const> tf::MessageFilterJointState::MEvent |
Definition at line 52 of file effort_display.h.
|
inline |
Constructor.
tf | The tf::Transformer this filter should use |
target_frame | The frame this filter should attempt to transform to. To use multiple frames, pass an empty string here and use the setTargetFrames() function. |
queue_size | The number of messages to queue up before throwing away old ones. 0 means infinite (dangerous). |
nh | The NodeHandle to use for any necessary operations |
max_rate | The maximum rate to check for newly transformable messages |
Definition at line 72 of file effort_display.h.
|
inline |
Constructor.
f | The filter to connect this filter's input to. Often will be a message_filters::Subscriber. |
tf | The tf::Transformer this filter should use |
target_frame | The frame this filter should attempt to transform to. To use multiple frames, pass an empty string here and use the setTargetFrames() function. |
queue_size | The number of messages to queue up before throwing away old ones. 0 means infinite (dangerous). |
nh | The NodeHandle to use for any necessary operations |
max_rate | The maximum rate to check for newly transformable messages |
Definition at line 95 of file effort_display.h.
|
inline |
Destructor.
Definition at line 122 of file effort_display.h.
|
inline |
Definition at line 197 of file effort_display.h.
|
inline |
Manually add a message into this filter.
Definition at line 232 of file effort_display.h.
|
inlineprivate |
Definition at line 426 of file effort_display.h.
|
inlinevirtual |
Clear any messages currently in the queue.
Implements tf::MessageFilterBase.
Definition at line 184 of file effort_display.h.
|
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.
|
inlineprivate |
Definition at line 454 of file effort_display.h.
|
inlinevirtual |
Reimplemented from tf::MessageFilter< sensor_msgs::JointState >.
Definition at line 254 of file effort_display.h.
|
inline |
Get the target frames as a string for debugging.
Definition at line 167 of file effort_display.h.
|
inlineprivate |
Callback that happens when we receive a message on the message topic.
Definition at line 414 of file effort_display.h.
|
inlineprivate |
Definition at line 261 of file effort_display.h.
|
inlineprivate |
Definition at line 399 of file effort_display.h.
|
inline |
Register a callback to be called when a message is about to be dropped.
callback | The callback to call |
Definition at line 243 of file effort_display.h.
tf::MessageFilterJointState::ROS_STATIC_ASSERT | ( | ros::message_traits::HasHeader< M >::value | ) |
|
inlinevirtual |
Reimplemented from tf::MessageFilter< sensor_msgs::JointState >.
Definition at line 249 of file effort_display.h.
|
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.
|
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.
|
inlinevirtual |
Set the required tolerance for the notifier to return true.
Implements tf::MessageFilterBase.
Definition at line 176 of file effort_display.h.
|
inlineprivate |
Definition at line 460 of file effort_display.h.
|
inlineprivate |
Definition at line 282 of file effort_display.h.
|
inlineprivate |
Definition at line 373 of file effort_display.h.
|
inlineprivate |
Definition at line 419 of file effort_display.h.
|
private |
Definition at line 490 of file effort_display.h.
|
private |
Definition at line 487 of file effort_display.h.
|
private |
Definition at line 486 of file effort_display.h.
|
private |
Definition at line 506 of file effort_display.h.
|
private |
Definition at line 507 of file effort_display.h.
|
private |
Definition at line 489 of file effort_display.h.
|
private |
Definition at line 493 of file effort_display.h.
|
private |
Definition at line 492 of file effort_display.h.
|
private |
Definition at line 468 of file effort_display.h.
|
private |
Definition at line 469 of file effort_display.h.
|
private |
Definition at line 504 of file effort_display.h.
|
private |
The number of messages in the list. Used because messages_.size() has linear cost.
Definition at line 476 of file effort_display.h.
|
private |
The message list.
Definition at line 475 of file effort_display.h.
|
private |
The mutex used for locking message list operations.
Definition at line 477 of file effort_display.h.
|
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.
|
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.
|
private |
Definition at line 495 of file effort_display.h.
|
private |
The node used to subscribe to the topic.
Definition at line 467 of file effort_display.h.
|
private |
The maximum number of messages we queue up.
Definition at line 473 of file effort_display.h.
|
private |
Definition at line 485 of file effort_display.h.
|
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.
|
private |
Definition at line 471 of file effort_display.h.
|
private |
Definition at line 472 of file effort_display.h.
|
private |
The Transformer used to determine if transformation data is available.
Definition at line 466 of file effort_display.h.
|
private |
Definition at line 502 of file effort_display.h.
|
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.
|
private |
Definition at line 488 of file effort_display.h.
|
private |
Definition at line 483 of file effort_display.h.
|
private |
Definition at line 482 of file effort_display.h.