35 #include "tf2_msgs/TF2Error.h"
38 #include <console_bridge/console.h>
40 #include <boost/foreach.hpp>
50 {
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));}
55 msg.translation.x =
tf2.getOrigin().x();
56 msg.translation.y =
tf2.getOrigin().y();
57 msg.translation.z =
tf2.getOrigin().z();
58 msg.rotation.x =
tf2.getRotation().x();
59 msg.rotation.y =
tf2.getRotation().y();
60 msg.rotation.z =
tf2.getRotation().z();
61 msg.rotation.w =
tf2.getRotation().w();
68 msg.header.stamp = stamp;
69 msg.header.frame_id = frame_id;
70 msg.child_frame_id = child_frame_id;
75 msg.translation.x = pos.x();
76 msg.translation.y = pos.y();
77 msg.translation.z = pos.z();
78 msg.rotation.x = orient.x();
79 msg.rotation.y = orient.y();
80 msg.rotation.z = orient.z();
81 msg.rotation.w = orient.w();
87 msg.header.stamp = stamp;
88 msg.header.frame_id = frame_id;
89 msg.child_frame_id = child_frame_id;
105 if (frame_id.size() > 0)
106 if (frame_id[0] ==
'/')
113 std::string out = in;
122 if (frame_id.size() == 0)
124 std::stringstream ss;
125 ss <<
"Invalid argument passed to "<< function_name_arg <<
" in tf2 frame_ids cannot be empty";
126 CONSOLE_BRIDGE_logWarn(
"%s",ss.str().c_str());
132 std::stringstream ss;
133 ss <<
"Invalid argument \"" << frame_id <<
"\" passed to "<< function_name_arg <<
" in tf2 frame_ids cannot start with a '/' like: ";
134 CONSOLE_BRIDGE_logWarn(
"%s",ss.str().c_str());
143 if (frame_id.empty())
145 std::stringstream ss;
146 ss <<
"Invalid argument passed to "<< function_name_arg <<
" in tf2 frame_ids cannot be empty";
152 std::stringstream ss;
153 ss <<
"Invalid argument \"" << frame_id <<
"\" passed to "<< function_name_arg <<
" in tf2 frame_ids cannot start with a '/' like: ";
160 std::stringstream ss;
161 ss <<
"\"" << frame_id <<
"\" passed to "<< function_name_arg <<
" does not exist. ";
169 : cache_time_(cache_time)
170 , transformable_callbacks_counter_(0)
171 , transformable_requests_counter_(0)
172 , using_dedicated_thread_(false)
192 for (std::vector<TimeCacheInterfacePtr>::iterator cache_it =
frames_.begin() + 1; cache_it !=
frames_.end(); ++cache_it)
195 (*cache_it)->clearList();
213 geometry_msgs::TransformStamped stripped = transform_in;
214 stripped.header.frame_id =
stripSlash(stripped.header.frame_id);
215 stripped.child_frame_id =
stripSlash(stripped.child_frame_id);
218 bool error_exists =
false;
219 if (stripped.child_frame_id == stripped.header.frame_id)
221 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());
225 if (stripped.child_frame_id ==
"")
227 CONSOLE_BRIDGE_logError(
"TF_NO_CHILD_FRAME_ID: Ignoring transform from authority \"%s\" because child_frame_id not set ", authority.c_str());
231 if (stripped.header.frame_id ==
"")
233 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());
237 if (std::isnan(stripped.transform.translation.x) || std::isnan(stripped.transform.translation.y) || std::isnan(stripped.transform.translation.z)||
238 std::isnan(stripped.transform.rotation.x) || std::isnan(stripped.transform.rotation.y) || std::isnan(stripped.transform.rotation.z) || std::isnan(stripped.transform.rotation.w))
240 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)",
241 stripped.child_frame_id.c_str(), authority.c_str(),
242 stripped.transform.translation.x, stripped.transform.translation.y, stripped.transform.translation.z,
243 stripped.transform.rotation.x, stripped.transform.rotation.y, stripped.transform.rotation.z, stripped.transform.rotation.w
248 bool valid = std::abs((stripped.transform.rotation.w * stripped.transform.rotation.w
249 + stripped.transform.rotation.x * stripped.transform.rotation.x
250 + stripped.transform.rotation.y * stripped.transform.rotation.y
255 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)",
256 stripped.child_frame_id.c_str(), authority.c_str(),
257 stripped.transform.rotation.x, stripped.transform.rotation.y, stripped.transform.rotation.z, stripped.transform.rotation.w);
271 std::string error_string;
278 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());
312 return walkToTopParent(f, time, target_id, source_id, error_string, NULL);
317 CompactFrameID source_id, std::string* error_string, std::vector<CompactFrameID>
321 frame_chain->clear();
324 if (source_id == target_id)
327 return tf2_msgs::TF2Error::NO_ERROR;
334 if (retval != tf2_msgs::TF2Error::NO_ERROR)
345 std::string extrapolation_error_string;
346 bool extrapolation_might_have_occurred =
false;
352 frame_chain->push_back(frame);
361 CompactFrameID parent = f.gather(cache, time, error_string ? &extrapolation_error_string : NULL);
366 extrapolation_might_have_occurred =
true;
371 if (frame == target_id)
374 return tf2_msgs::TF2Error::NO_ERROR;
387 std::stringstream ss;
388 ss <<
"The tf tree is invalid because it contains a loop." << std::endl
390 *error_string = ss.str();
392 return tf2_msgs::TF2Error::LOOKUP_ERROR;
399 std::vector<CompactFrameID> reverse_frame_chain;
401 while (frame != top_parent)
405 reverse_frame_chain.push_back(frame);
419 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());
423 return tf2_msgs::TF2Error::EXTRAPOLATION_ERROR;
427 if (frame == source_id)
433 frame_chain->swap(reverse_frame_chain);
435 std::reverse(frame_chain->begin(), frame_chain->end());
437 return tf2_msgs::TF2Error::NO_ERROR;
449 std::stringstream ss;
450 ss <<
"The tf tree is invalid because it contains a loop." << std::endl
452 *error_string = ss.str();
454 return tf2_msgs::TF2Error::LOOKUP_ERROR;
458 if (frame != top_parent)
460 if (extrapolation_might_have_occurred)
466 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());
470 return tf2_msgs::TF2Error::EXTRAPOLATION_ERROR;
475 return tf2_msgs::TF2Error::CONNECTIVITY_ERROR;
477 else if (frame_chain){
479 reverse_frame_chain.push_back(frame);
486 int m = reverse_frame_chain.size()-1;
487 int n = frame_chain->size()-1;
488 for (; m >= 0 && n >= 0; --m, --n)
490 if ((*frame_chain)[n] != reverse_frame_chain[m])
499 frame_chain->erase(frame_chain->begin() + (n + 2), frame_chain->end());
501 if (m < reverse_frame_chain.size())
503 for (
int i = m; i >= 0; --i)
505 frame_chain->push_back(reverse_frame_chain[i]);
510 return tf2_msgs::TF2Error::NO_ERROR;
529 if (!cache->getData(
time,
st, error_string))
595 const std::string& source_frame,
600 if (target_frame == source_frame) {
601 geometry_msgs::TransformStamped identity;
602 identity.header.frame_id = target_frame;
603 identity.child_frame_id = source_frame;
604 identity.transform.rotation.w = 1;
611 identity.header.stamp = cache->getLatestTimestamp();
613 identity.header.stamp = time;
616 identity.header.stamp = time;
625 std::string error_string;
627 int retval =
walkToTopParent(accum, time, target_id, source_id, &error_string);
628 if (retval != tf2_msgs::TF2Error::NO_ERROR)
632 case tf2_msgs::TF2Error::CONNECTIVITY_ERROR:
634 case tf2_msgs::TF2Error::EXTRAPOLATION_ERROR:
636 case tf2_msgs::TF2Error::LOOKUP_ERROR:
644 geometry_msgs::TransformStamped output_transform;
646 return output_transform;
652 const std::string& source_frame,
654 const std::string& fixed_frame)
const
656 validateFrameId(
"lookupTransform argument target_frame", target_frame);
657 validateFrameId(
"lookupTransform argument source_frame", source_frame);
660 geometry_msgs::TransformStamped output;
661 geometry_msgs::TransformStamped temp1 =
lookupTransform(fixed_frame, source_frame, source_time);
662 geometry_msgs::TransformStamped temp2 =
lookupTransform(target_frame, fixed_frame, target_time);
668 output.header.stamp = temp2.header.stamp;
669 output.header.frame_id = target_frame;
670 output.child_frame_id = source_frame;
744 return cache->getParent(time, error_string);
759 const ros::Time& time, std::string* error_msg)
const
761 if (target_id == 0 || source_id == 0)
767 *error_msg += std::string(
"target_frame: " +
lookupFrameString(target_id ) +
" does not exist.");
773 *error_msg += std::string(
" ");
781 if (target_id == source_id)
787 if (
walkToTopParent(accum, time, target_id, source_id, error_msg) == tf2_msgs::TF2Error::NO_ERROR)
796 const ros::Time& time, std::string* error_msg)
const
803 const ros::Time& time, std::string* error_msg)
const
806 if (target_frame == source_frame)
809 if (
warnFrameId(
"canTransform argument target_frame", target_frame))
811 if (
warnFrameId(
"canTransform argument source_frame", source_frame))
819 if (target_id == 0 || source_id == 0)
825 *error_msg += std::string(
"canTransform: target_frame " + target_frame +
" does not exist.");
831 *error_msg += std::string(
" ");
833 *error_msg += std::string(
"canTransform: source_frame " + source_frame +
" does not exist.");
842 const std::string& source_frame,
const ros::Time& source_time,
843 const std::string& fixed_frame, std::string* error_msg)
const
845 if (
warnFrameId(
"canTransform argument target_frame", target_frame))
847 if (
warnFrameId(
"canTransform argument source_frame", source_frame))
849 if (
warnFrameId(
"canTransform argument fixed_frame", fixed_frame))
857 if (target_id == 0 || source_id == 0 || fixed_id == 0)
863 *error_msg += std::string(
"canTransform: target_frame " + target_frame +
" does not exist.");
869 *error_msg += std::string(
" ");
871 *error_msg += std::string(
"canTransform: source_frame " + source_frame +
" does not exist.");
875 if (target_id == 0 || source_id == 0)
877 *error_msg += std::string(
" ");
879 *error_msg += std::string(
"fixed_frame: " + fixed_frame +
"does not exist.");
890 if (frame_id >=
frames_.size())
901 M_StringToCompactFrameID::const_iterator map_it =
frameIDs_.find(frameid_str);
907 retval = map_it->second;
914 M_StringToCompactFrameID::iterator map_it =
frameIDs_.find(frameid_str);
932 std::stringstream ss;
933 ss <<
"Reverse lookup of frame id " << frame_id_num <<
" failed!";
946 *out = std::string(
"Could not find a connection between '"+
lookupFrameString(target_frame)+
"' and '"+
948 "Tf has two or more unconnected trees.");
959 std::stringstream mstream;
966 for (
unsigned int counter = 1; counter <
frames_.size(); counter ++)
969 if (frame_ptr == NULL)
972 if( frame_ptr->getData(
ros::Time(), temp))
981 return mstream.str();
992 return rhs.second ==
id;
1001 if (source_id == 0 || target_id == 0)
return tf2_msgs::TF2Error::LOOKUP_ERROR;
1003 if (source_id == target_id)
1008 time = cache->getLatestTimestamp();
1011 return tf2_msgs::TF2Error::NO_ERROR;
1014 std::vector<P_TimeAndFrameID> lct_cache;
1034 if (latest.second == 0)
1040 if (!latest.first.isZero())
1042 common_time = std::min(latest.first, common_time);
1045 lct_cache.push_back(latest);
1047 frame = latest.second;
1050 if (frame == target_id)
1057 return tf2_msgs::TF2Error::NO_ERROR;
1065 std::stringstream ss;
1066 ss<<
"The tf tree is invalid because it contains a loop." << std::endl
1068 *error_string = ss.str();
1070 return tf2_msgs::TF2Error::LOOKUP_ERROR;
1090 if (latest.second == 0)
1095 if (!latest.first.isZero())
1097 common_time = std::min(latest.first, common_time);
1100 std::vector<P_TimeAndFrameID>::iterator it = std::find_if(lct_cache.begin(), lct_cache.end(),
TimeAndFrameIDFrameComparator(latest.second));
1101 if (it != lct_cache.end())
1103 common_parent = it->second;
1107 frame = latest.second;
1110 if (frame == source_id)
1117 return tf2_msgs::TF2Error::NO_ERROR;
1125 std::stringstream ss;
1126 ss<<
"The tf tree is invalid because it contains a loop." << std::endl
1128 *error_string = ss.str();
1130 return tf2_msgs::TF2Error::LOOKUP_ERROR;
1134 if (common_parent == 0)
1137 return tf2_msgs::TF2Error::CONNECTIVITY_ERROR;
1142 std::vector<P_TimeAndFrameID>::iterator it = lct_cache.begin();
1143 std::vector<P_TimeAndFrameID>::iterator end = lct_cache.end();
1144 for (; it != end; ++it)
1146 if (!it->first.isZero())
1148 common_time = std::min(common_time, it->first);
1151 if (it->second == common_parent)
1164 return tf2_msgs::TF2Error::NO_ERROR;
1169 std::stringstream mstream;
1177 mstream.precision(3);
1178 mstream.setf(std::ios::fixed,std::ios::floatfield);
1181 for (
unsigned int counter = 1; counter <
frames_.size(); counter ++)
1198 std::string authority =
"no recorded authority";
1199 std::map<CompactFrameID, std::string>::const_iterator it =
frame_authority_.find(cfid);
1201 authority = it->second;
1204 double rate = cache->getListLength() / std::max((cache->getLatestTimestamp().toSec() -
1205 cache->getOldestTimestamp().toSec() ), 0.0001);
1207 mstream << std::fixed;
1208 mstream.precision(3);
1210 mstream <<
" parent: '" <<
frameIDs_reverse[frame_id_num] <<
"'" << std::endl;
1211 mstream <<
" broadcaster: '" << authority <<
"'" << std::endl;
1212 mstream <<
" rate: " << rate << std::endl;
1213 mstream <<
" most_recent_transform: " << (cache->getLatestTimestamp()).toSec() << std::endl;
1214 mstream <<
" oldest_transform: " << (cache->getOldestTimestamp()).toSec() << std::endl;
1215 if ( current_time > 0 ) {
1216 mstream <<
" transform_delay: " << current_time - cache->getLatestTimestamp().toSec() << std::endl;
1218 mstream <<
" buffer_length: " << (cache->getLatestTimestamp() - cache->getOldestTimestamp()).toSec() << std::endl;
1221 return mstream.str();
1275 if (target_frame == source_frame)
1299 return 0xffffffffffffffffULL;
1400 for (
unsigned int counter = 1; counter <
frameIDs_reverse.size(); counter ++)
1417 std::vector<TransformableTuple> transformables;
1458 transformables.push_back(boost::make_tuple(boost::ref(it->second),
1462 boost::ref(req.
time),
1463 boost::ref(result)));
1483 BOOST_FOREACH (TransformableTuple tt, transformables)
1485 tt.get<0>()(tt.get<1>(), tt.get<2>(), tt.get<3>(), tt.get<4>(), tt.get<5>());
1495 std::stringstream mstream;
1496 mstream <<
"digraph G {" << std::endl;
1502 mstream <<
"\"no tf data recieved\"";
1504 mstream.precision(3);
1505 mstream.setf(std::ios::fixed,std::ios::floatfield);
1507 for (
unsigned int counter = 1; counter <
frames_.size(); counter ++)
1509 unsigned int frame_id_num;
1511 if (!counter_frame) {
1514 if(!counter_frame->getData(
ros::Time(), temp)) {
1519 std::string authority =
"no recorded authority";
1520 std::map<unsigned int, std::string>::const_iterator it =
frame_authority_.find(counter);
1522 authority = it->second;
1524 double rate = counter_frame->getListLength() / std::max((counter_frame->getLatestTimestamp().toSec() -
1525 counter_frame->getOldestTimestamp().toSec()), 0.0001);
1527 mstream << std::fixed;
1528 mstream.precision(3);
1532 <<
"Broadcaster: " << authority <<
"\\n"
1533 <<
"Average rate: " << rate <<
" Hz\\n"
1534 <<
"Most recent transform: " << (counter_frame->getLatestTimestamp()).toSec() <<
" ";
1535 if (current_time > 0)
1536 mstream <<
"( "<< current_time - counter_frame->getLatestTimestamp().toSec() <<
" sec old)";
1541 <<
"Buffer length: " << (counter_frame->getLatestTimestamp()-counter_frame->getOldestTimestamp()).toSec() <<
" sec\\n"
1542 <<
"\"];" <<std::endl;
1545 for (
unsigned int counter = 1; counter <
frames_.size(); counter ++)
1547 unsigned int frame_id_num;
1549 if (!counter_frame) {
1550 if (current_time > 0) {
1551 mstream <<
"edge [style=invis];" <<std::endl;
1552 mstream <<
" subgraph cluster_legend { style=bold; color=black; label =\"view_frames Result\";\n"
1553 <<
"\"Recorded at time: " << current_time <<
"\"[ shape=plaintext ] ;\n "
1558 if (counter_frame->getData(
ros::Time(), temp)) {
1566 mstream <<
"edge [style=invis];" <<std::endl;
1567 mstream <<
" subgraph cluster_legend { style=bold; color=black; label =\"view_frames Result\";\n";
1568 if (current_time > 0)
1569 mstream <<
"\"Recorded at time: " << current_time <<
"\"[ shape=plaintext ] ;\n ";
1570 mstream <<
"}" <<
"->" <<
"\"" <<
frameIDs_reverse[counter] <<
"\";" << std::endl;
1574 return mstream.str();
1584 std::string error_string;
1588 std::stringstream mstream;
1598 std::vector<CompactFrameID> source_frame_chain;
1599 int retval =
walkToTopParent(accum, source_time, fixed_id, source_id, &error_string, &source_frame_chain);
1601 if (retval != tf2_msgs::TF2Error::NO_ERROR)
1605 case tf2_msgs::TF2Error::CONNECTIVITY_ERROR:
1607 case tf2_msgs::TF2Error::EXTRAPOLATION_ERROR:
1609 case tf2_msgs::TF2Error::LOOKUP_ERROR:
1617 std::vector<CompactFrameID> target_frame_chain;
1618 retval =
walkToTopParent(accum, target_time, target_id, fixed_id, &error_string, &target_frame_chain);
1620 if (retval != tf2_msgs::TF2Error::NO_ERROR)
1624 case tf2_msgs::TF2Error::CONNECTIVITY_ERROR:
1626 case tf2_msgs::TF2Error::EXTRAPOLATION_ERROR:
1628 case tf2_msgs::TF2Error::LOOKUP_ERROR:
1636 if (source_frame_chain.size() > 0 && target_frame_chain.size() > 0 &&
1637 source_frame_chain.back() == target_frame_chain.front())
1639 source_frame_chain.pop_back();
1642 for (
unsigned int i = 0; i < target_frame_chain.size(); ++i)
1644 source_frame_chain.push_back(target_frame_chain[i]);
1649 for (
unsigned int i = 0; i < source_frame_chain.size(); ++i)
1658 return buffer.
walkToTopParent(accum, time, target_id, source_id, error_string, frame_chain);