Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
tf_remapper_cpp::TfRemapperNode Class Reference

A node that remaps TF frame names according to the given set of rules. More...

#include <tf_remapper_node.h>

Public Member Functions

 TfRemapperNode ()
 
virtual ~TfRemapperNode ()
 

Protected Member Functions

void addToStaticTfCache (const tf2_msgs::TFMessage &message, tf2_msgs::TFMessage &cache) const
 Add the given TF message to the static TF cache. Newer TFs overwrite the older ones. More...
 
void oldTfCallback (const ros::MessageEvent< tf2_msgs::TFMessage const > &event)
 The remapper that actually changes the TF messages in reverse direction. More...
 
void remappedTfCallback (const ros::MessageEvent< tf2_msgs::TFMessage const > &event)
 Callback when a TF message arrives on the remapped TF topic. More...
 

Protected Attributes

ros::Publisher oldTfPublisher
 Publisher of /tf. More...
 
ros::Subscriber oldTfSubscriber
 Private ROS node handle. More...
 
std::string oldTfTopic
 Cache of static TF messages in the reverse direction. More...
 
ros::NodeHandle privateNodeHandle
 ROS node handle. More...
 
ros::NodeHandle publicNodeHandle
 
ros::Publisher remappedTfPublisher
 Subscriber to /tf (only in bidirectional mode). More...
 
ros::Subscriber remappedTfSubscriber
 Subscriber to /tf_old. More...
 
std::string remappedTfTopic
 Name of the old topic ("/tf_old"). More...
 
tf2_msgs::TFMessage reverseStaticTfCache
 Cache of static TF messages. More...
 
TfRemapper reverseTfRemapper
 The remapper that actually changes the TF messages. More...
 
bool staticTf
 Publisher of /tf_old (only in bidirectional mode). More...
 
tf2_msgs::TFMessage staticTfCache
 If true, this node works with static TF, which need special care. More...
 
TfRemapper tfRemapper
 Name of the remapped topic ("/tf"). More...
 

Detailed Description

A node that remaps TF frame names according to the given set of rules.

Parameters:

Definition at line 23 of file tf_remapper_node.h.

Constructor & Destructor Documentation

◆ TfRemapperNode()

tf_remapper_cpp::TfRemapperNode::TfRemapperNode ( )

Start the node.

Exceptions
ros::InvalidParameterExceptionif the 'mappings' parameter has invalid value.

Definition at line 4 of file tf_remapper_node.cpp.

◆ ~TfRemapperNode()

virtual tf_remapper_cpp::TfRemapperNode::~TfRemapperNode ( )
inlinevirtual

Definition at line 29 of file tf_remapper_node.h.

Member Function Documentation

◆ addToStaticTfCache()

void tf_remapper_cpp::TfRemapperNode::addToStaticTfCache ( const tf2_msgs::TFMessage &  message,
tf2_msgs::TFMessage &  cache 
) const
protected

Add the given TF message to the static TF cache. Newer TFs overwrite the older ones.

Parameters
messageThe message to add.
cacheThe cache to update.

Definition at line 102 of file tf_remapper_node.cpp.

◆ oldTfCallback()

void tf_remapper_cpp::TfRemapperNode::oldTfCallback ( const ros::MessageEvent< tf2_msgs::TFMessage const > &  event)
protected

The remapper that actually changes the TF messages in reverse direction.

Callback when a TF message arrives on the old TF topic.

Parameters
eventThe TF message.

Definition at line 66 of file tf_remapper_node.cpp.

◆ remappedTfCallback()

void tf_remapper_cpp::TfRemapperNode::remappedTfCallback ( const ros::MessageEvent< tf2_msgs::TFMessage const > &  event)
protected

Callback when a TF message arrives on the remapped TF topic.

Parameters
eventThe TF message.

Definition at line 84 of file tf_remapper_node.cpp.

Member Data Documentation

◆ oldTfPublisher

ros::Publisher tf_remapper_cpp::TfRemapperNode::oldTfPublisher
protected

Publisher of /tf.

Definition at line 37 of file tf_remapper_node.h.

◆ oldTfSubscriber

ros::Subscriber tf_remapper_cpp::TfRemapperNode::oldTfSubscriber
protected

Private ROS node handle.

Definition at line 34 of file tf_remapper_node.h.

◆ oldTfTopic

std::string tf_remapper_cpp::TfRemapperNode::oldTfTopic
protected

Cache of static TF messages in the reverse direction.

Definition at line 43 of file tf_remapper_node.h.

◆ privateNodeHandle

ros::NodeHandle tf_remapper_cpp::TfRemapperNode::privateNodeHandle
protected

ROS node handle.

Definition at line 33 of file tf_remapper_node.h.

◆ publicNodeHandle

ros::NodeHandle tf_remapper_cpp::TfRemapperNode::publicNodeHandle
protected

Definition at line 29 of file tf_remapper_node.h.

◆ remappedTfPublisher

ros::Publisher tf_remapper_cpp::TfRemapperNode::remappedTfPublisher
protected

Subscriber to /tf (only in bidirectional mode).

Definition at line 36 of file tf_remapper_node.h.

◆ remappedTfSubscriber

ros::Subscriber tf_remapper_cpp::TfRemapperNode::remappedTfSubscriber
protected

Subscriber to /tf_old.

Definition at line 35 of file tf_remapper_node.h.

◆ remappedTfTopic

std::string tf_remapper_cpp::TfRemapperNode::remappedTfTopic
protected

Name of the old topic ("/tf_old").

Definition at line 44 of file tf_remapper_node.h.

◆ reverseStaticTfCache

tf2_msgs::TFMessage tf_remapper_cpp::TfRemapperNode::reverseStaticTfCache
protected

Cache of static TF messages.

Definition at line 41 of file tf_remapper_node.h.

◆ reverseTfRemapper

TfRemapper tf_remapper_cpp::TfRemapperNode::reverseTfRemapper
protected

The remapper that actually changes the TF messages.

Definition at line 47 of file tf_remapper_node.h.

◆ staticTf

bool tf_remapper_cpp::TfRemapperNode::staticTf
protected

Publisher of /tf_old (only in bidirectional mode).

Definition at line 39 of file tf_remapper_node.h.

◆ staticTfCache

tf2_msgs::TFMessage tf_remapper_cpp::TfRemapperNode::staticTfCache
protected

If true, this node works with static TF, which need special care.

Definition at line 40 of file tf_remapper_node.h.

◆ tfRemapper

TfRemapper tf_remapper_cpp::TfRemapperNode::tfRemapper
protected

Name of the remapped topic ("/tf").

Definition at line 46 of file tf_remapper_node.h.


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


tf_remapper_cpp
Author(s): Martin Pecka
autogenerated on Mon Feb 28 2022 23:52:08