10 for (TfRemapper::MappingsType::const_iterator it = mappings.begin(); it != mappings.end(); ++it) {
11 if (it->first.empty())
16 this->mappings = mappings;
18 for (std::map<std::string, std::string>::const_iterator it = mappings.begin(); it != mappings.end(); ++it) {
19 if (!it->second.empty())
20 this->mappings[it->second] = it->first;
29 for (
size_t i = 0; i < mappingsParam.
size(); ++i) {
36 const std::string oldKey = (reverse ?
"new" :
"old");
37 const std::string newKey = (reverse ?
"old" :
"new");
42 if (it->first == oldKey)
43 oldTopic = (
const std::string&)it->second;
44 else if (it->first == newKey)
45 newTopic = (std::string&)it->second;
50 if (oldTopic.empty() && newTopic.empty())
54 if (oldTopic == newTopic)
55 ROS_WARN_STREAM(
"Remapped topic '" << oldTopic <<
"' is the same as the old topic.");
57 if (!oldTopic.empty())
58 this->mappings[oldTopic] = newTopic;
63 tf2_msgs::TFMessage message = inMessage;
64 this->doRemapping(message);
69 for (std::vector<geometry_msgs::TransformStamped>::iterator it = message.transforms.begin();
70 it != message.transforms.end(); ) {
71 geometry_msgs::TransformStamped& transform = *it;
72 if (this->mappings.find(transform.header.frame_id) != this->mappings.end()) {
73 if (this->mappings.at(transform.header.frame_id).empty()) {
74 it = message.transforms.erase(it);
77 transform.header.frame_id = this->mappings.at(transform.header.frame_id);
80 if (this->mappings.find(transform.child_frame_id) != this->mappings.end()) {
81 if (this->mappings.at(transform.child_frame_id).empty()) {
82 it = message.transforms.erase(it);
85 transform.child_frame_id = this->mappings.at(transform.child_frame_id);
93 return this->mappings;