1 #ifndef TF_REMAPPER_NODE_CPP_TF_REMAPPER_H 2 #define TF_REMAPPER_NODE_CPP_TF_REMAPPER_H 5 #include <tf2_msgs/TFMessage.h> 60 void addToStaticTfCache(
const tf2_msgs::TFMessage& message, tf2_msgs::TFMessage& cache)
const;
65 #endif //TF_REMAPPER_NODE_CPP_TF_REMAPPER_H TfRemapper reverseTfRemapper
The remapper that actually changes the TF messages.
virtual ~TfRemapperNode()
TfRemapper tfRemapper
Name of the remapped topic ("/tf").
Remap frames in TF messages according to given rules.
tf2_msgs::TFMessage staticTfCache
If true, this node works with static TF, which need special care.
ros::Publisher oldTfPublisher
Publisher of /tf.
A node that remaps TF frame names according to the given set of rules.
ros::Subscriber remappedTfSubscriber
Subscriber to /tf_old.
ros::NodeHandle privateNodeHandle
ROS node handle.
tf2_msgs::TFMessage reverseStaticTfCache
Cache of static TF messages.
std::string remappedTfTopic
Name of the old topic ("/tf_old").
ros::Publisher remappedTfPublisher
Subscriber to /tf (only in bidirectional mode).
void oldTfCallback(const ros::MessageEvent< tf2_msgs::TFMessage const > &event)
The remapper that actually changes the TF messages in reverse direction.
ros::Subscriber oldTfSubscriber
Private ROS node handle.
void remappedTfCallback(const ros::MessageEvent< tf2_msgs::TFMessage const > &event)
Callback when a TF message arrives on the remapped TF topic.
bool staticTf
Publisher of /tf_old (only in bidirectional mode).
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.
ros::NodeHandle publicNodeHandle
std::string oldTfTopic
Cache of static TF messages in the reverse direction.