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. | |
| void | oldTfCallback (const ros::MessageEvent< tf2_msgs::TFMessage const > &event) |
| The remapper that actually changes the TF messages in reverse direction. | |
| void | remappedTfCallback (const ros::MessageEvent< tf2_msgs::TFMessage const > &event) |
| Callback when a TF message arrives on the remapped TF topic. | |
Protected Attributes | |
| ros::Publisher | oldTfPublisher |
| Publisher of /tf. | |
| ros::Subscriber | oldTfSubscriber |
| Private ROS node handle. | |
| std::string | oldTfTopic |
| Cache of static TF messages in the reverse direction. | |
| ros::NodeHandle | privateNodeHandle |
| ROS node handle. | |
| ros::NodeHandle | publicNodeHandle |
| ros::Publisher | remappedTfPublisher |
| Subscriber to /tf (only in bidirectional mode). | |
| ros::Subscriber | remappedTfSubscriber |
| Subscriber to /tf_old. | |
| std::string | remappedTfTopic |
| Name of the old topic ("/tf_old"). | |
| tf2_msgs::TFMessage | reverseStaticTfCache |
| Cache of static TF messages. | |
| TfRemapper | reverseTfRemapper |
| The remapper that actually changes the TF messages. | |
| bool | staticTf |
| Publisher of /tf_old (only in bidirectional mode). | |
| tf2_msgs::TFMessage | staticTfCache |
| If true, this node works with static TF, which need special care. | |
| TfRemapper | tfRemapper |
| Name of the remapped topic ("/tf"). | |
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.
Start the node.
| ros::InvalidParameterException | if the 'mappings' parameter has invalid value. |
Definition at line 4 of file tf_remapper_node.cpp.
| virtual tf_remapper_cpp::TfRemapperNode::~TfRemapperNode | ( | ) | [inline, virtual] |
Definition at line 29 of file tf_remapper_node.h.
| 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.
| message | The message to add. |
| cache | The cache to update. |
Definition at line 102 of file tf_remapper_node.cpp.
| 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.
| event | The TF message. |
Definition at line 66 of file tf_remapper_node.cpp.
| 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.
| event | The TF message. |
Definition at line 84 of file tf_remapper_node.cpp.
Publisher of /tf.
Definition at line 37 of file tf_remapper_node.h.
Private ROS node handle.
Definition at line 34 of file tf_remapper_node.h.
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.
ROS node handle.
Definition at line 33 of file tf_remapper_node.h.
Definition at line 29 of file tf_remapper_node.h.
Subscriber to /tf (only in bidirectional mode).
Definition at line 36 of file tf_remapper_node.h.
Subscriber to /tf_old.
Definition at line 35 of file tf_remapper_node.h.
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.
tf2_msgs::TFMessage tf_remapper_cpp::TfRemapperNode::reverseStaticTfCache [protected] |
Cache of static TF messages.
Definition at line 41 of file tf_remapper_node.h.
The remapper that actually changes the TF messages.
Definition at line 47 of file tf_remapper_node.h.
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.
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.
Name of the remapped topic ("/tf").
Definition at line 46 of file tf_remapper_node.h.