Go to the documentation of this file.
   13         this->
staticTf = this->remappedTfTopic == 
"tf_static" || this->remappedTfTopic == 
"/tf_static";
 
   18     if (!hasMappingsParam) {
 
   20         ROS_WARN(
"The 'mappings' parameter to tf_remap is missing");
 
   30         ROS_INFO_STREAM(
"Applying the following mappings" << (bidirectional ? 
" bidirectionally" : 
"") <<
 
   31                         " to incoming tf frame ids:");
 
   34             ROS_INFO_STREAM(
"* " << it->first << 
" " << (bidirectional && !it->second.empty() ? 
"<" : 
"") << 
"-> " <<
 
   35                                     (it->second.empty() ? 
"DELETE" : it->second));
 
   40                 if (it->second.empty())
 
   51         ROS_INFO(
"Running in static TF mode (caching all TFs, latched publisher)");
 
   68     const std::string& callerid = 
event.getPublisherName();
 
   72     tf2_msgs::TFMessage message = this->tfRemapper.doRemapping(*event.
getConstMessage());
 
   77         this->addToStaticTfCache(message, this->staticTfCache);
 
   78         this->remappedTfPublisher.publish(this->staticTfCache);
 
   80         this->remappedTfPublisher.publish(message);
 
   86     const std::string& callerid = 
event.getPublisherName();
 
   90     tf2_msgs::TFMessage message = this->reverseTfRemapper.doRemapping(*event.
getConstMessage());
 
   95         this->addToStaticTfCache(message, this->reverseStaticTfCache);
 
   96         this->oldTfPublisher.publish(this->reverseStaticTfCache);
 
   98         this->oldTfPublisher.publish(message);
 
  103         const tf2_msgs::TFMessage& message, tf2_msgs::TFMessage& cache)
 const {
 
  105     for (std::vector<geometry_msgs::TransformStamped>::const_iterator it = message.transforms.begin();
 
  106             it != message.transforms.end(); ++it) {
 
  108         for (std::vector<geometry_msgs::TransformStamped>::iterator cacheIt = cache.transforms.begin();
 
  109                 cacheIt != cache.transforms.end(); ++cacheIt) {
 
  110             if (it->child_frame_id == cacheIt->child_frame_id) {
 
  117             cache.transforms.push_back(*it);
 
  121 int main(
int argc, 
char * argv[])
 
  
A node that remaps TF frame names according to the given set of rules.
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
const MappingsType & getMappings() const
Get the mappings this remapper uses.
bool getParam(const std::string &key, bool &b) const
ros::Subscriber oldTfSubscriber
Private ROS node handle.
int main(int argc, char *argv[])
ros::NodeHandle publicNodeHandle
std::string remappedTfTopic
Name of the old topic ("/tf_old").
ros::NodeHandle privateNodeHandle
ROS node handle.
TfRemapper reverseTfRemapper
The remapper that actually changes the TF messages.
ros::Publisher remappedTfPublisher
Subscriber to /tf (only in bidirectional mode).
const boost::shared_ptr< ConstMessage > & getConstMessage() const
Publisher advertise(AdvertiseOptions &ops)
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.
bool hasParam(const std::string &key) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
#define ROS_INFO_STREAM(args)
TfRemapper tfRemapper
Name of the remapped topic ("/tf").
Remap frames in TF messages according to given rules.
std::string oldTfTopic
Cache of static TF messages in the reverse direction.
ros::Publisher oldTfPublisher
Publisher of /tf.
const ROSCPP_DECL std::string & getName()
void oldTfCallback(const ros::MessageEvent< tf2_msgs::TFMessage const > &event)
The remapper that actually changes the TF messages in reverse direction.
T param(const std::string ¶m_name, const T &default_val) const
void remappedTfCallback(const ros::MessageEvent< tf2_msgs::TFMessage const > &event)
Callback when a TF message arrives on the remapped TF topic.
ros::Subscriber remappedTfSubscriber
Subscriber to /tf_old.
tf_remapper_cpp
Author(s): Martin Pecka 
autogenerated on Mon May 2 2022 02:25:06