35 #include "tf2_msgs/TF2Error.h"
38 #include <console_bridge/console.h>
40 #include <boost/foreach.hpp>
41 #include <boost/tuple/tuple.hpp>
51 {
tf2 =
tf2::Transform(
tf2::Quaternion(msg.rotation.x, msg.rotation.y, msg.rotation.z, msg.rotation.w), tf2::Vector3(msg.translation.x, msg.translation.y, msg.translation.z));}
56 msg.translation.x =
tf2.getOrigin().x();
57 msg.translation.y =
tf2.getOrigin().y();
58 msg.translation.z =
tf2.getOrigin().z();
59 msg.rotation.x =
tf2.getRotation().x();
60 msg.rotation.y =
tf2.getRotation().y();
61 msg.rotation.z =
tf2.getRotation().z();
62 msg.rotation.w =
tf2.getRotation().w();
69 msg.header.stamp = stamp;
70 msg.header.frame_id = frame_id;
71 msg.child_frame_id = child_frame_id;
76 msg.translation.x = pos.x();
77 msg.translation.y = pos.y();
78 msg.translation.z = pos.z();
79 msg.rotation.x = orient.x();
80 msg.rotation.y = orient.y();
81 msg.rotation.z = orient.z();
82 msg.rotation.w = orient.w();
88 msg.header.stamp = stamp;
89 msg.header.frame_id = frame_id;
90 msg.child_frame_id = child_frame_id;
106 if (frame_id.size() > 0)
107 if (frame_id[0] ==
'/')
114 std::string out = in;
123 if (frame_id.size() == 0)
125 std::stringstream ss;
126 ss <<
"Invalid argument passed to "<< function_name_arg <<
" in tf2 frame_ids cannot be empty";
127 CONSOLE_BRIDGE_logWarn(
"%s",ss.str().c_str());
133 std::stringstream ss;
134 ss <<
"Invalid argument \"" << frame_id <<
"\" passed to "<< function_name_arg <<
" in tf2 frame_ids cannot start with a '/' like: ";
135 CONSOLE_BRIDGE_logWarn(
"%s",ss.str().c_str());
144 if (frame_id.empty())
146 std::stringstream ss;
147 ss <<
"Invalid argument passed to "<< function_name_arg <<
" in tf2 frame_ids cannot be empty";
153 std::stringstream ss;
154 ss <<
"Invalid argument \"" << frame_id <<
"\" passed to "<< function_name_arg <<
" in tf2 frame_ids cannot start with a '/' like: ";
161 std::stringstream ss;
162 ss <<
"\"" << frame_id <<
"\" passed to "<< function_name_arg <<
" does not exist. ";
170 : cache_time_(cache_time)
171 , transformable_callbacks_counter_(0)
172 , transformable_requests_counter_(0)
173 , using_dedicated_thread_(false)
193 for (std::vector<TimeCacheInterfacePtr>::iterator cache_it =
frames_.begin() + 1; cache_it !=
frames_.end(); ++cache_it)
196 (*cache_it)->clearList();
214 geometry_msgs::TransformStamped stripped = transform_in;
215 stripped.header.frame_id =
stripSlash(stripped.header.frame_id);
216 stripped.child_frame_id =
stripSlash(stripped.child_frame_id);
219 bool error_exists =
false;
220 if (stripped.child_frame_id == stripped.header.frame_id)
222 CONSOLE_BRIDGE_logError(
"TF_SELF_TRANSFORM: Ignoring transform from authority \"%s\" with frame_id and child_frame_id \"%s\" because they are the same", authority.c_str(), stripped.child_frame_id.c_str());
226 if (stripped.child_frame_id ==
"")
228 CONSOLE_BRIDGE_logError(
"TF_NO_CHILD_FRAME_ID: Ignoring transform from authority \"%s\" because child_frame_id not set ", authority.c_str());
232 if (stripped.header.frame_id ==
"")
234 CONSOLE_BRIDGE_logError(
"TF_NO_FRAME_ID: Ignoring transform with child_frame_id \"%s\" from authority \"%s\" because frame_id not set", stripped.child_frame_id.c_str(), authority.c_str());
238 if (std::isnan(stripped.transform.translation.x) || std::isnan(stripped.transform.translation.y) || std::isnan(stripped.transform.translation.z)||
239 std::isnan(stripped.transform.rotation.x) || std::isnan(stripped.transform.rotation.y) || std::isnan(stripped.transform.rotation.z) || std::isnan(stripped.transform.rotation.w))
241 CONSOLE_BRIDGE_logError(
"TF_NAN_INPUT: Ignoring transform for child_frame_id \"%s\" from authority \"%s\" because of a nan value in the transform (%f %f %f) (%f %f %f %f)",
242 stripped.child_frame_id.c_str(), authority.c_str(),
243 stripped.transform.translation.x, stripped.transform.translation.y, stripped.transform.translation.z,
244 stripped.transform.rotation.x, stripped.transform.rotation.y, stripped.transform.rotation.z, stripped.transform.rotation.w
249 bool valid = std::abs((stripped.transform.rotation.w * stripped.transform.rotation.w
250 + stripped.transform.rotation.x * stripped.transform.rotation.x
251 + stripped.transform.rotation.y * stripped.transform.rotation.y
256 CONSOLE_BRIDGE_logError(
"TF_DENORMALIZED_QUATERNION: Ignoring transform for child_frame_id \"%s\" from authority \"%s\" because of an invalid quaternion in the transform (%f %f %f %f)",
257 stripped.child_frame_id.c_str(), authority.c_str(),
258 stripped.transform.rotation.x, stripped.transform.rotation.y, stripped.transform.rotation.z, stripped.transform.rotation.w);
272 std::string error_string;
279 CONSOLE_BRIDGE_logWarn((error_string+
" for frame %s (parent %s) at time %lf according to authority %s").c_str(), stripped.child_frame_id.c_str(), stripped.header.frame_id.c_str(), stripped.header.stamp.toSec(), authority.c_str());
313 return walkToTopParent(f, time, target_id, source_id, error_string, NULL);
318 CompactFrameID source_id, std::string* error_string, std::vector<CompactFrameID>
322 frame_chain->clear();
325 if (source_id == target_id)
328 return tf2_msgs::TF2Error::NO_ERROR;
335 if (retval != tf2_msgs::TF2Error::NO_ERROR)
346 std::string extrapolation_error_string;
347 bool extrapolation_might_have_occurred =
false;
353 frame_chain->push_back(frame);
362 CompactFrameID parent = f.gather(cache, time, error_string ? &extrapolation_error_string : NULL);
367 extrapolation_might_have_occurred =
true;
372 if (frame == target_id)
375 return tf2_msgs::TF2Error::NO_ERROR;
388 std::stringstream ss;
389 ss <<
"The tf tree is invalid because it contains a loop." << std::endl
391 *error_string = ss.str();
393 return tf2_msgs::TF2Error::LOOKUP_ERROR;
400 std::vector<CompactFrameID> reverse_frame_chain;
402 while (frame != top_parent)
406 reverse_frame_chain.push_back(frame);
420 snprintf(str,
sizeof(str),
"%s, when looking up transform from frame [%s] to frame [%s]", error_string->c_str(),
lookupFrameString(source_id).c_str(),
lookupFrameString(target_id).c_str());
424 return tf2_msgs::TF2Error::EXTRAPOLATION_ERROR;
428 if (frame == source_id)
434 frame_chain->swap(reverse_frame_chain);
436 std::reverse(frame_chain->begin(), frame_chain->end());
438 return tf2_msgs::TF2Error::NO_ERROR;
450 std::stringstream ss;
451 ss <<
"The tf tree is invalid because it contains a loop." << std::endl
453 *error_string = ss.str();
455 return tf2_msgs::TF2Error::LOOKUP_ERROR;
459 if (frame != top_parent)
461 if (extrapolation_might_have_occurred)
467 snprintf(str,
sizeof(str),
"%s, when looking up transform from frame [%s] to frame [%s]", extrapolation_error_string.c_str(),
lookupFrameString(source_id).c_str(),
lookupFrameString(target_id).c_str());
471 return tf2_msgs::TF2Error::EXTRAPOLATION_ERROR;
476 return tf2_msgs::TF2Error::CONNECTIVITY_ERROR;
478 else if (frame_chain){
480 reverse_frame_chain.push_back(frame);
487 int m = reverse_frame_chain.size()-1;
488 int n = frame_chain->size()-1;
489 for (; m >= 0 && n >= 0; --m, --n)
491 if ((*frame_chain)[n] != reverse_frame_chain[m])
500 frame_chain->erase(frame_chain->begin() + (n + 2), frame_chain->end());
502 if (m < reverse_frame_chain.size())
504 for (
int i = m; i >= 0; --i)
506 frame_chain->push_back(reverse_frame_chain[i]);
511 return tf2_msgs::TF2Error::NO_ERROR;
530 if (!cache->getData(
time,
st, error_string))
596 const std::string& source_frame,
601 if (target_frame == source_frame) {
602 geometry_msgs::TransformStamped identity;
603 identity.header.frame_id = target_frame;
604 identity.child_frame_id = source_frame;
605 identity.transform.rotation.w = 1;
612 identity.header.stamp = cache->getLatestTimestamp();
614 identity.header.stamp = time;
617 identity.header.stamp = time;
626 std::string error_string;
628 int retval =
walkToTopParent(accum, time, target_id, source_id, &error_string);
629 if (retval != tf2_msgs::TF2Error::NO_ERROR)
633 case tf2_msgs::TF2Error::CONNECTIVITY_ERROR:
635 case tf2_msgs::TF2Error::EXTRAPOLATION_ERROR:
637 case tf2_msgs::TF2Error::LOOKUP_ERROR:
645 geometry_msgs::TransformStamped output_transform;
647 return output_transform;
653 const std::string& source_frame,
655 const std::string& fixed_frame)
const
657 validateFrameId(
"lookupTransform argument target_frame", target_frame);
658 validateFrameId(
"lookupTransform argument source_frame", source_frame);
661 geometry_msgs::TransformStamped output;
662 geometry_msgs::TransformStamped temp1 =
lookupTransform(fixed_frame, source_frame, source_time);
663 geometry_msgs::TransformStamped temp2 =
lookupTransform(target_frame, fixed_frame, target_time);
669 output.header.stamp = temp2.header.stamp;
670 output.header.frame_id = target_frame;
671 output.child_frame_id = source_frame;
745 return cache->getParent(time, error_string);
760 const ros::Time& time, std::string* error_msg)
const
762 if (target_id == 0 || source_id == 0)
768 *error_msg += std::string(
"target_frame: " +
lookupFrameString(target_id ) +
" does not exist.");
774 *error_msg += std::string(
" ");
782 if (target_id == source_id)
788 if (
walkToTopParent(accum, time, target_id, source_id, error_msg) == tf2_msgs::TF2Error::NO_ERROR)
797 const ros::Time& time, std::string* error_msg)
const
804 const ros::Time& time, std::string* error_msg)
const
807 if (target_frame == source_frame)
810 if (
warnFrameId(
"canTransform argument target_frame", target_frame))
812 if (
warnFrameId(
"canTransform argument source_frame", source_frame))
820 if (target_id == 0 || source_id == 0)
826 *error_msg += std::string(
"canTransform: target_frame " + target_frame +
" does not exist.");
832 *error_msg += std::string(
" ");
834 *error_msg += std::string(
"canTransform: source_frame " + source_frame +
" does not exist.");
843 const std::string& source_frame,
const ros::Time& source_time,
844 const std::string& fixed_frame, std::string* error_msg)
const
846 if (
warnFrameId(
"canTransform argument target_frame", target_frame))
848 if (
warnFrameId(
"canTransform argument source_frame", source_frame))
850 if (
warnFrameId(
"canTransform argument fixed_frame", fixed_frame))
858 if (target_id == 0 || source_id == 0 || fixed_id == 0)
864 *error_msg += std::string(
"canTransform: target_frame " + target_frame +
" does not exist.");
870 *error_msg += std::string(
" ");
872 *error_msg += std::string(
"canTransform: source_frame " + source_frame +
" does not exist.");
876 if (target_id == 0 || source_id == 0)
878 *error_msg += std::string(
" ");
880 *error_msg += std::string(
"fixed_frame: " + fixed_frame +
"does not exist.");
891 if (frame_id >=
frames_.size())
902 M_StringToCompactFrameID::const_iterator map_it =
frameIDs_.find(frameid_str);
908 retval = map_it->second;
915 M_StringToCompactFrameID::iterator map_it =
frameIDs_.find(frameid_str);
933 std::stringstream ss;
934 ss <<
"Reverse lookup of frame id " << frame_id_num <<
" failed!";
947 *out = std::string(
"Could not find a connection between '"+
lookupFrameString(target_frame)+
"' and '"+
949 "Tf has two or more unconnected trees.");
960 std::stringstream mstream;
967 for (
unsigned int counter = 1; counter <
frames_.size(); counter ++)
970 if (frame_ptr == NULL)
973 if( frame_ptr->getData(
ros::Time(), temp))
982 return mstream.str();
993 return rhs.second ==
id;
1002 if (source_id == 0 || target_id == 0)
return tf2_msgs::TF2Error::LOOKUP_ERROR;
1004 if (source_id == target_id)
1009 time = cache->getLatestTimestamp();
1012 return tf2_msgs::TF2Error::NO_ERROR;
1015 std::vector<P_TimeAndFrameID> lct_cache;
1035 if (latest.second == 0)
1041 if (!latest.first.isZero())
1043 common_time = std::min(latest.first, common_time);
1046 lct_cache.push_back(latest);
1048 frame = latest.second;
1051 if (frame == target_id)
1058 return tf2_msgs::TF2Error::NO_ERROR;
1066 std::stringstream ss;
1067 ss<<
"The tf tree is invalid because it contains a loop." << std::endl
1069 *error_string = ss.str();
1071 return tf2_msgs::TF2Error::LOOKUP_ERROR;
1091 if (latest.second == 0)
1096 if (!latest.first.isZero())
1098 common_time = std::min(latest.first, common_time);
1101 std::vector<P_TimeAndFrameID>::iterator it = std::find_if(lct_cache.begin(), lct_cache.end(),
TimeAndFrameIDFrameComparator(latest.second));
1102 if (it != lct_cache.end())
1104 common_parent = it->second;
1108 frame = latest.second;
1111 if (frame == source_id)
1118 return tf2_msgs::TF2Error::NO_ERROR;
1126 std::stringstream ss;
1127 ss<<
"The tf tree is invalid because it contains a loop." << std::endl
1129 *error_string = ss.str();
1131 return tf2_msgs::TF2Error::LOOKUP_ERROR;
1135 if (common_parent == 0)
1138 return tf2_msgs::TF2Error::CONNECTIVITY_ERROR;
1143 std::vector<P_TimeAndFrameID>::iterator it = lct_cache.begin();
1144 std::vector<P_TimeAndFrameID>::iterator end = lct_cache.end();
1145 for (; it != end; ++it)
1147 if (!it->first.isZero())
1149 common_time = std::min(common_time, it->first);
1152 if (it->second == common_parent)
1165 return tf2_msgs::TF2Error::NO_ERROR;
1170 std::stringstream mstream;
1178 mstream.precision(3);
1179 mstream.setf(std::ios::fixed,std::ios::floatfield);
1182 for (
unsigned int counter = 1; counter <
frames_.size(); counter ++)
1199 std::string authority =
"no recorded authority";
1200 std::map<CompactFrameID, std::string>::const_iterator it =
frame_authority_.find(cfid);
1202 authority = it->second;
1205 double rate = cache->getListLength() / std::max((cache->getLatestTimestamp().toSec() -
1206 cache->getOldestTimestamp().toSec() ), 0.0001);
1208 mstream << std::fixed;
1209 mstream.precision(3);
1211 mstream <<
" parent: '" <<
frameIDs_reverse[frame_id_num] <<
"'" << std::endl;
1212 mstream <<
" broadcaster: '" << authority <<
"'" << std::endl;
1213 mstream <<
" rate: " << rate << std::endl;
1214 mstream <<
" most_recent_transform: " << (cache->getLatestTimestamp()).toSec() << std::endl;
1215 mstream <<
" oldest_transform: " << (cache->getOldestTimestamp()).toSec() << std::endl;
1216 if ( current_time > 0 ) {
1217 mstream <<
" transform_delay: " << current_time - cache->getLatestTimestamp().toSec() << std::endl;
1219 mstream <<
" buffer_length: " << (cache->getLatestTimestamp() - cache->getOldestTimestamp()).toSec() << std::endl;
1222 return mstream.str();
1276 if (target_frame == source_frame)
1300 return 0xffffffffffffffffULL;
1401 for (
unsigned int counter = 1; counter <
frameIDs_reverse.size(); counter ++)
1418 std::vector<TransformableTuple> transformables;
1459 transformables.push_back(boost::make_tuple(boost::ref(it->second),
1463 boost::ref(req.
time),
1464 boost::ref(result)));
1484 BOOST_FOREACH (TransformableTuple tt, transformables)
1486 tt.get<0>()(tt.get<1>(), tt.get<2>(), tt.get<3>(), tt.get<4>(), tt.get<5>());
1496 std::stringstream mstream;
1497 mstream <<
"digraph G {" << std::endl;
1503 mstream <<
"\"no tf data recieved\"";
1505 mstream.precision(3);
1506 mstream.setf(std::ios::fixed,std::ios::floatfield);
1508 for (
unsigned int counter = 1; counter <
frames_.size(); counter ++)
1510 unsigned int frame_id_num;
1512 if (!counter_frame) {
1515 if(!counter_frame->getData(
ros::Time(), temp)) {
1520 std::string authority =
"no recorded authority";
1521 std::map<unsigned int, std::string>::const_iterator it =
frame_authority_.find(counter);
1523 authority = it->second;
1525 double rate = counter_frame->getListLength() / std::max((counter_frame->getLatestTimestamp().toSec() -
1526 counter_frame->getOldestTimestamp().toSec()), 0.0001);
1528 mstream << std::fixed;
1529 mstream.precision(3);
1533 <<
"Broadcaster: " << authority <<
"\\n"
1534 <<
"Average rate: " << rate <<
" Hz\\n"
1535 <<
"Most recent transform: " << (counter_frame->getLatestTimestamp()).toSec() <<
" ";
1536 if (current_time > 0)
1537 mstream <<
"( "<< current_time - counter_frame->getLatestTimestamp().toSec() <<
" sec old)";
1542 <<
"Buffer length: " << (counter_frame->getLatestTimestamp()-counter_frame->getOldestTimestamp()).toSec() <<
" sec\\n"
1543 <<
"\"];" <<std::endl;
1546 for (
unsigned int counter = 1; counter <
frames_.size(); counter ++)
1548 unsigned int frame_id_num;
1550 if (!counter_frame) {
1551 if (current_time > 0) {
1552 mstream <<
"edge [style=invis];" <<std::endl;
1553 mstream <<
" subgraph cluster_legend { style=bold; color=black; label =\"view_frames Result\";\n"
1554 <<
"\"Recorded at time: " << current_time <<
"\"[ shape=plaintext ] ;\n "
1559 if (counter_frame->getData(
ros::Time(), temp)) {
1567 mstream <<
"edge [style=invis];" <<std::endl;
1568 mstream <<
" subgraph cluster_legend { style=bold; color=black; label =\"view_frames Result\";\n";
1569 if (current_time > 0)
1570 mstream <<
"\"Recorded at time: " << current_time <<
"\"[ shape=plaintext ] ;\n ";
1571 mstream <<
"}" <<
"->" <<
"\"" <<
frameIDs_reverse[counter] <<
"\";" << std::endl;
1575 return mstream.str();
1585 std::string error_string;
1589 std::stringstream mstream;
1599 std::vector<CompactFrameID> source_frame_chain;
1600 int retval =
walkToTopParent(accum, source_time, fixed_id, source_id, &error_string, &source_frame_chain);
1602 if (retval != tf2_msgs::TF2Error::NO_ERROR)
1606 case tf2_msgs::TF2Error::CONNECTIVITY_ERROR:
1608 case tf2_msgs::TF2Error::EXTRAPOLATION_ERROR:
1610 case tf2_msgs::TF2Error::LOOKUP_ERROR:
1618 std::vector<CompactFrameID> target_frame_chain;
1619 retval =
walkToTopParent(accum, target_time, target_id, fixed_id, &error_string, &target_frame_chain);
1621 if (retval != tf2_msgs::TF2Error::NO_ERROR)
1625 case tf2_msgs::TF2Error::CONNECTIVITY_ERROR:
1627 case tf2_msgs::TF2Error::EXTRAPOLATION_ERROR:
1629 case tf2_msgs::TF2Error::LOOKUP_ERROR:
1637 if (source_frame_chain.size() > 0 && target_frame_chain.size() > 0 &&
1638 source_frame_chain.back() == target_frame_chain.front())
1640 source_frame_chain.pop_back();
1643 for (
unsigned int i = 0; i < target_frame_chain.size(); ++i)
1645 source_frame_chain.push_back(target_frame_chain[i]);
1650 for (
unsigned int i = 0; i < source_frame_chain.size(); ++i)
1659 return buffer.
walkToTopParent(accum, time, target_id, source_id, error_string, frame_chain);