35 #include "tf2_msgs/TF2Error.h"
38 #include <console_bridge/console.h>
49 {
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));}
54 msg.translation.x =
tf2.getOrigin().x();
55 msg.translation.y =
tf2.getOrigin().y();
56 msg.translation.z =
tf2.getOrigin().z();
57 msg.rotation.x =
tf2.getRotation().x();
58 msg.rotation.y =
tf2.getRotation().y();
59 msg.rotation.z =
tf2.getRotation().z();
60 msg.rotation.w =
tf2.getRotation().w();
67 msg.header.stamp = stamp;
68 msg.header.frame_id = frame_id;
69 msg.child_frame_id = child_frame_id;
74 msg.translation.x = pos.x();
75 msg.translation.y = pos.y();
76 msg.translation.z = pos.z();
77 msg.rotation.x = orient.x();
78 msg.rotation.y = orient.y();
79 msg.rotation.z = orient.z();
80 msg.rotation.w = orient.w();
86 msg.header.stamp = stamp;
87 msg.header.frame_id = frame_id;
88 msg.child_frame_id = child_frame_id;
104 if (frame_id.size() > 0)
105 if (frame_id[0] ==
'/')
112 std::string out = in;
121 if (frame_id.size() == 0)
123 std::stringstream ss;
124 ss <<
"Invalid argument passed to "<< function_name_arg <<
" in tf2 frame_ids cannot be empty";
125 CONSOLE_BRIDGE_logWarn(
"%s",ss.str().c_str());
131 std::stringstream ss;
132 ss <<
"Invalid argument \"" << frame_id <<
"\" passed to "<< function_name_arg <<
" in tf2 frame_ids cannot start with a '/' like: ";
133 CONSOLE_BRIDGE_logWarn(
"%s",ss.str().c_str());
142 if (frame_id.empty())
144 std::stringstream ss;
145 ss <<
"Invalid argument passed to "<< function_name_arg <<
" in tf2 frame_ids cannot be empty";
151 std::stringstream ss;
152 ss <<
"Invalid argument \"" << frame_id <<
"\" passed to "<< function_name_arg <<
" in tf2 frame_ids cannot start with a '/' like: ";
159 std::stringstream ss;
160 ss <<
"\"" << frame_id <<
"\" passed to "<< function_name_arg <<
" does not exist. ";
168 : cache_time_(cache_time)
169 , transformable_callbacks_counter_(0)
170 , transformable_requests_counter_(0)
171 , using_dedicated_thread_(false)
191 for (std::vector<TimeCacheInterfacePtr>::iterator cache_it =
frames_.begin() + 1; cache_it !=
frames_.end(); ++cache_it)
194 (*cache_it)->clearList();
212 geometry_msgs::TransformStamped stripped = transform_in;
213 stripped.header.frame_id =
stripSlash(stripped.header.frame_id);
214 stripped.child_frame_id =
stripSlash(stripped.child_frame_id);
217 bool error_exists =
false;
218 if (stripped.child_frame_id == stripped.header.frame_id)
220 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());
224 if (stripped.child_frame_id ==
"")
226 CONSOLE_BRIDGE_logError(
"TF_NO_CHILD_FRAME_ID: Ignoring transform from authority \"%s\" because child_frame_id not set ", authority.c_str());
230 if (stripped.header.frame_id ==
"")
232 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());
236 if (std::isnan(stripped.transform.translation.x) || std::isnan(stripped.transform.translation.y) || std::isnan(stripped.transform.translation.z)||
237 std::isnan(stripped.transform.rotation.x) || std::isnan(stripped.transform.rotation.y) || std::isnan(stripped.transform.rotation.z) || std::isnan(stripped.transform.rotation.w))
239 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)",
240 stripped.child_frame_id.c_str(), authority.c_str(),
241 stripped.transform.translation.x, stripped.transform.translation.y, stripped.transform.translation.z,
242 stripped.transform.rotation.x, stripped.transform.rotation.y, stripped.transform.rotation.z, stripped.transform.rotation.w
247 bool valid = std::abs((stripped.transform.rotation.w * stripped.transform.rotation.w
248 + stripped.transform.rotation.x * stripped.transform.rotation.x
249 + stripped.transform.rotation.y * stripped.transform.rotation.y
254 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)",
255 stripped.child_frame_id.c_str(), authority.c_str(),
256 stripped.transform.rotation.x, stripped.transform.rotation.y, stripped.transform.rotation.z, stripped.transform.rotation.w);
270 std::string error_string;
277 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());
311 return walkToTopParent(f, time, target_id, source_id, error_string, NULL);
316 CompactFrameID source_id, std::string* error_string, std::vector<CompactFrameID>
320 frame_chain->clear();
323 if (source_id == target_id)
326 return tf2_msgs::TF2Error::NO_ERROR;
333 if (retval != tf2_msgs::TF2Error::NO_ERROR)
344 std::string extrapolation_error_string;
345 bool extrapolation_might_have_occurred =
false;
351 frame_chain->push_back(frame);
360 CompactFrameID parent = f.gather(cache, time, error_string ? &extrapolation_error_string : NULL);
365 extrapolation_might_have_occurred =
true;
370 if (frame == target_id)
373 return tf2_msgs::TF2Error::NO_ERROR;
386 std::stringstream ss;
387 ss <<
"The tf tree is invalid because it contains a loop." << std::endl
389 *error_string = ss.str();
391 return tf2_msgs::TF2Error::LOOKUP_ERROR;
398 std::vector<CompactFrameID> reverse_frame_chain;
400 while (frame != top_parent)
404 reverse_frame_chain.push_back(frame);
418 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());
422 return tf2_msgs::TF2Error::EXTRAPOLATION_ERROR;
426 if (frame == source_id)
432 frame_chain->swap(reverse_frame_chain);
434 std::reverse(frame_chain->begin(), frame_chain->end());
436 return tf2_msgs::TF2Error::NO_ERROR;
448 std::stringstream ss;
449 ss <<
"The tf tree is invalid because it contains a loop." << std::endl
451 *error_string = ss.str();
453 return tf2_msgs::TF2Error::LOOKUP_ERROR;
457 if (frame != top_parent)
459 if (extrapolation_might_have_occurred)
465 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());
469 return tf2_msgs::TF2Error::EXTRAPOLATION_ERROR;
474 return tf2_msgs::TF2Error::CONNECTIVITY_ERROR;
476 else if (frame_chain){
478 reverse_frame_chain.push_back(frame);
485 int m = reverse_frame_chain.size()-1;
486 int n = frame_chain->size()-1;
487 for (; m >= 0 && n >= 0; --m, --n)
489 if ((*frame_chain)[n] != reverse_frame_chain[m])
498 frame_chain->erase(frame_chain->begin() + (n + 2), frame_chain->end());
500 if (m < reverse_frame_chain.size())
502 for (
int i = m; i >= 0; --i)
504 frame_chain->push_back(reverse_frame_chain[i]);
509 return tf2_msgs::TF2Error::NO_ERROR;
528 if (!cache->getData(
time,
st, error_string))
594 const std::string& source_frame,
599 if (target_frame == source_frame) {
600 geometry_msgs::TransformStamped identity;
601 identity.header.frame_id = target_frame;
602 identity.child_frame_id = source_frame;
603 identity.transform.rotation.w = 1;
610 identity.header.stamp = cache->getLatestTimestamp();
612 identity.header.stamp = time;
615 identity.header.stamp = time;
624 std::string error_string;
626 int retval =
walkToTopParent(accum, time, target_id, source_id, &error_string);
627 if (retval != tf2_msgs::TF2Error::NO_ERROR)
631 case tf2_msgs::TF2Error::CONNECTIVITY_ERROR:
633 case tf2_msgs::TF2Error::EXTRAPOLATION_ERROR:
635 case tf2_msgs::TF2Error::LOOKUP_ERROR:
643 geometry_msgs::TransformStamped output_transform;
645 return output_transform;
651 const std::string& source_frame,
653 const std::string& fixed_frame)
const
655 validateFrameId(
"lookupTransform argument target_frame", target_frame);
656 validateFrameId(
"lookupTransform argument source_frame", source_frame);
659 geometry_msgs::TransformStamped output;
660 geometry_msgs::TransformStamped temp1 =
lookupTransform(fixed_frame, source_frame, source_time);
661 geometry_msgs::TransformStamped temp2 =
lookupTransform(target_frame, fixed_frame, target_time);
667 output.header.stamp = temp2.header.stamp;
668 output.header.frame_id = target_frame;
669 output.child_frame_id = source_frame;
743 return cache->getParent(time, error_string);
758 const ros::Time& time, std::string* error_msg)
const
760 if (target_id == 0 || source_id == 0)
766 *error_msg += std::string(
"target_frame: " +
lookupFrameString(target_id ) +
" does not exist.");
772 *error_msg += std::string(
" ");
780 if (target_id == source_id)
786 if (
walkToTopParent(accum, time, target_id, source_id, error_msg) == tf2_msgs::TF2Error::NO_ERROR)
795 const ros::Time& time, std::string* error_msg)
const
802 const ros::Time& time, std::string* error_msg)
const
805 if (target_frame == source_frame)
808 if (
warnFrameId(
"canTransform argument target_frame", target_frame))
810 if (
warnFrameId(
"canTransform argument source_frame", source_frame))
818 if (target_id == 0 || source_id == 0)
824 *error_msg += std::string(
"canTransform: target_frame " + target_frame +
" does not exist.");
830 *error_msg += std::string(
" ");
832 *error_msg += std::string(
"canTransform: source_frame " + source_frame +
" does not exist.");
841 const std::string& source_frame,
const ros::Time& source_time,
842 const std::string& fixed_frame, std::string* error_msg)
const
844 if (
warnFrameId(
"canTransform argument target_frame", target_frame))
846 if (
warnFrameId(
"canTransform argument source_frame", source_frame))
848 if (
warnFrameId(
"canTransform argument fixed_frame", fixed_frame))
856 if (target_id == 0 || source_id == 0 || fixed_id == 0)
862 *error_msg += std::string(
"canTransform: target_frame " + target_frame +
" does not exist.");
868 *error_msg += std::string(
" ");
870 *error_msg += std::string(
"canTransform: source_frame " + source_frame +
" does not exist.");
874 if (target_id == 0 || source_id == 0)
876 *error_msg += std::string(
" ");
878 *error_msg += std::string(
"fixed_frame: " + fixed_frame +
"does not exist.");
889 if (frame_id >=
frames_.size())
900 M_StringToCompactFrameID::const_iterator map_it =
frameIDs_.find(frameid_str);
906 retval = map_it->second;
913 M_StringToCompactFrameID::iterator map_it =
frameIDs_.find(frameid_str);
931 std::stringstream ss;
932 ss <<
"Reverse lookup of frame id " << frame_id_num <<
" failed!";
945 *out = std::string(
"Could not find a connection between '"+
lookupFrameString(target_frame)+
"' and '"+
947 "Tf has two or more unconnected trees.");
958 std::stringstream mstream;
965 for (
unsigned int counter = 1; counter <
frames_.size(); counter ++)
968 if (frame_ptr == NULL)
971 if( frame_ptr->getData(
ros::Time(), temp))
980 return mstream.str();
991 return rhs.second ==
id;
1000 if (source_id == 0 || target_id == 0)
return tf2_msgs::TF2Error::LOOKUP_ERROR;
1002 if (source_id == target_id)
1007 time = cache->getLatestTimestamp();
1010 return tf2_msgs::TF2Error::NO_ERROR;
1013 std::vector<P_TimeAndFrameID> lct_cache;
1033 if (latest.second == 0)
1039 if (!latest.first.isZero())
1041 common_time = std::min(latest.first, common_time);
1044 lct_cache.push_back(latest);
1046 frame = latest.second;
1049 if (frame == target_id)
1056 return tf2_msgs::TF2Error::NO_ERROR;
1064 std::stringstream ss;
1065 ss<<
"The tf tree is invalid because it contains a loop." << std::endl
1067 *error_string = ss.str();
1069 return tf2_msgs::TF2Error::LOOKUP_ERROR;
1089 if (latest.second == 0)
1094 if (!latest.first.isZero())
1096 common_time = std::min(latest.first, common_time);
1099 std::vector<P_TimeAndFrameID>::iterator it = std::find_if(lct_cache.begin(), lct_cache.end(),
TimeAndFrameIDFrameComparator(latest.second));
1100 if (it != lct_cache.end())
1102 common_parent = it->second;
1106 frame = latest.second;
1109 if (frame == source_id)
1116 return tf2_msgs::TF2Error::NO_ERROR;
1124 std::stringstream ss;
1125 ss<<
"The tf tree is invalid because it contains a loop." << std::endl
1127 *error_string = ss.str();
1129 return tf2_msgs::TF2Error::LOOKUP_ERROR;
1133 if (common_parent == 0)
1136 return tf2_msgs::TF2Error::CONNECTIVITY_ERROR;
1141 std::vector<P_TimeAndFrameID>::iterator it = lct_cache.begin();
1142 std::vector<P_TimeAndFrameID>::iterator end = lct_cache.end();
1143 for (; it != end; ++it)
1145 if (!it->first.isZero())
1147 common_time = std::min(common_time, it->first);
1150 if (it->second == common_parent)
1163 return tf2_msgs::TF2Error::NO_ERROR;
1168 std::stringstream mstream;
1176 mstream.precision(3);
1177 mstream.setf(std::ios::fixed,std::ios::floatfield);
1180 for (
unsigned int counter = 1; counter <
frames_.size(); counter ++)
1197 std::string authority =
"no recorded authority";
1198 std::map<CompactFrameID, std::string>::const_iterator it =
frame_authority_.find(cfid);
1200 authority = it->second;
1203 double rate = cache->getListLength() / std::max((cache->getLatestTimestamp().toSec() -
1204 cache->getOldestTimestamp().toSec() ), 0.0001);
1206 mstream << std::fixed;
1207 mstream.precision(3);
1209 mstream <<
" parent: '" <<
frameIDs_reverse[frame_id_num] <<
"'" << std::endl;
1210 mstream <<
" broadcaster: '" << authority <<
"'" << std::endl;
1211 mstream <<
" rate: " << rate << std::endl;
1212 mstream <<
" most_recent_transform: " << (cache->getLatestTimestamp()).toSec() << std::endl;
1213 mstream <<
" oldest_transform: " << (cache->getOldestTimestamp()).toSec() << std::endl;
1214 if ( current_time > 0 ) {
1215 mstream <<
" transform_delay: " << current_time - cache->getLatestTimestamp().toSec() << std::endl;
1217 mstream <<
" buffer_length: " << (cache->getLatestTimestamp() - cache->getOldestTimestamp()).toSec() << std::endl;
1220 return mstream.str();
1274 if (target_frame == source_frame)
1298 return 0xffffffffffffffffULL;
1399 for (
unsigned int counter = 1; counter <
frameIDs_reverse.size(); counter ++)
1480 std::stringstream mstream;
1481 mstream <<
"digraph G {" << std::endl;
1487 mstream <<
"\"no tf data recieved\"";
1489 mstream.precision(3);
1490 mstream.setf(std::ios::fixed,std::ios::floatfield);
1492 for (
unsigned int counter = 1; counter <
frames_.size(); counter ++)
1494 unsigned int frame_id_num;
1496 if (!counter_frame) {
1499 if(!counter_frame->getData(
ros::Time(), temp)) {
1504 std::string authority =
"no recorded authority";
1505 std::map<unsigned int, std::string>::const_iterator it =
frame_authority_.find(counter);
1507 authority = it->second;
1509 double rate = counter_frame->getListLength() / std::max((counter_frame->getLatestTimestamp().toSec() -
1510 counter_frame->getOldestTimestamp().toSec()), 0.0001);
1512 mstream << std::fixed;
1513 mstream.precision(3);
1517 <<
"Broadcaster: " << authority <<
"\\n"
1518 <<
"Average rate: " << rate <<
" Hz\\n"
1519 <<
"Most recent transform: " << (counter_frame->getLatestTimestamp()).toSec() <<
" ";
1520 if (current_time > 0)
1521 mstream <<
"( "<< current_time - counter_frame->getLatestTimestamp().toSec() <<
" sec old)";
1526 <<
"Buffer length: " << (counter_frame->getLatestTimestamp()-counter_frame->getOldestTimestamp()).toSec() <<
" sec\\n"
1527 <<
"\"];" <<std::endl;
1530 for (
unsigned int counter = 1; counter <
frames_.size(); counter ++)
1532 unsigned int frame_id_num;
1534 if (!counter_frame) {
1535 if (current_time > 0) {
1536 mstream <<
"edge [style=invis];" <<std::endl;
1537 mstream <<
" subgraph cluster_legend { style=bold; color=black; label =\"view_frames Result\";\n"
1538 <<
"\"Recorded at time: " << current_time <<
"\"[ shape=plaintext ] ;\n "
1543 if (counter_frame->getData(
ros::Time(), temp)) {
1551 mstream <<
"edge [style=invis];" <<std::endl;
1552 mstream <<
" subgraph cluster_legend { style=bold; color=black; label =\"view_frames Result\";\n";
1553 if (current_time > 0)
1554 mstream <<
"\"Recorded at time: " << current_time <<
"\"[ shape=plaintext ] ;\n ";
1555 mstream <<
"}" <<
"->" <<
"\"" <<
frameIDs_reverse[counter] <<
"\";" << std::endl;
1559 return mstream.str();
1569 std::string error_string;
1573 std::stringstream mstream;
1583 std::vector<CompactFrameID> source_frame_chain;
1584 int retval =
walkToTopParent(accum, source_time, fixed_id, source_id, &error_string, &source_frame_chain);
1586 if (retval != tf2_msgs::TF2Error::NO_ERROR)
1590 case tf2_msgs::TF2Error::CONNECTIVITY_ERROR:
1592 case tf2_msgs::TF2Error::EXTRAPOLATION_ERROR:
1594 case tf2_msgs::TF2Error::LOOKUP_ERROR:
1602 std::vector<CompactFrameID> target_frame_chain;
1603 retval =
walkToTopParent(accum, target_time, target_id, fixed_id, &error_string, &target_frame_chain);
1605 if (retval != tf2_msgs::TF2Error::NO_ERROR)
1609 case tf2_msgs::TF2Error::CONNECTIVITY_ERROR:
1611 case tf2_msgs::TF2Error::EXTRAPOLATION_ERROR:
1613 case tf2_msgs::TF2Error::LOOKUP_ERROR:
1621 if (source_frame_chain.size() > 0 && target_frame_chain.size() > 0 &&
1622 source_frame_chain.back() == target_frame_chain.front())
1624 source_frame_chain.pop_back();
1627 for (
unsigned int i = 0; i < target_frame_chain.size(); ++i)
1629 source_frame_chain.push_back(target_frame_chain[i]);
1634 for (
unsigned int i = 0; i < source_frame_chain.size(); ++i)
1643 return buffer.
walkToTopParent(accum, time, target_id, source_id, error_string, frame_chain);