$search
00001 /* 00002 * Copyright (c) 2008, Willow Garage, Inc. 00003 * All rights reserved. 00004 * 00005 * Redistribution and use in source and binary forms, with or without 00006 * modification, are permitted provided that the following conditions are met: 00007 * 00008 * * Redistributions of source code must retain the above copyright 00009 * notice, this list of conditions and the following disclaimer. 00010 * * Redistributions in binary form must reproduce the above copyright 00011 * notice, this list of conditions and the following disclaimer in the 00012 * documentation and/or other materials provided with the distribution. 00013 * * Neither the name of the Willow Garage, Inc. nor the names of its 00014 * contributors may be used to endorse or promote products derived from 00015 * this software without specific prior written permission. 00016 * 00017 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00018 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00019 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00020 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00021 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00022 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00023 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00024 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00025 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00026 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00027 * POSSIBILITY OF SUCH DAMAGE. 00028 */ 00029 00032 #include "tf/tf.h" 00033 #include <sys/time.h> 00034 #include "ros/assert.h" 00035 #include "ros/ros.h" 00036 #include "angles/angles.h" 00037 00038 using namespace tf; 00039 00040 // Must provide storage for non-integral static const class members. 00041 // Otherwise you get undefined symbol errors on OS X (why not on Linux?). 00042 // Thanks to Rob for pointing out the right way to do this. 00043 const double tf::Transformer::DEFAULT_CACHE_TIME; 00044 00045 00046 enum WalkEnding 00047 { 00048 Identity, 00049 TargetParentOfSource, 00050 SourceParentOfTarget, 00051 FullPath, 00052 }; 00053 00054 struct CanTransformAccum 00055 { 00056 CompactFrameID gather(TimeCache* cache, ros::Time time, std::string* error_string) 00057 { 00058 return cache->getParent(time, error_string); 00059 } 00060 00061 void accum(bool source) 00062 { 00063 } 00064 00065 void finalize(WalkEnding end, ros::Time _time) 00066 { 00067 } 00068 00069 TransformStorage st; 00070 }; 00071 00072 struct TransformAccum 00073 { 00074 TransformAccum() 00075 : source_to_top_quat(0.0, 0.0, 0.0, 1.0) 00076 , source_to_top_vec(0.0, 0.0, 0.0) 00077 , target_to_top_quat(0.0, 0.0, 0.0, 1.0) 00078 , target_to_top_vec(0.0, 0.0, 0.0) 00079 , result_quat(0.0, 0.0, 0.0, 1.0) 00080 , result_vec(0.0, 0.0, 0.0) 00081 { 00082 } 00083 00084 CompactFrameID gather(TimeCache* cache, ros::Time time, std::string* error_string) 00085 { 00086 if (!cache->getData(time, st, error_string)) 00087 { 00088 return 0; 00089 } 00090 00091 return st.frame_id_; 00092 } 00093 00094 void accum(bool source) 00095 { 00096 if (source) 00097 { 00098 source_to_top_vec = quatRotate(st.rotation_, source_to_top_vec) + st.translation_; 00099 source_to_top_quat = st.rotation_ * source_to_top_quat; 00100 } 00101 else 00102 { 00103 target_to_top_vec = quatRotate(st.rotation_, target_to_top_vec) + st.translation_; 00104 target_to_top_quat = st.rotation_ * target_to_top_quat; 00105 } 00106 } 00107 00108 void finalize(WalkEnding end, ros::Time _time) 00109 { 00110 switch (end) 00111 { 00112 case Identity: 00113 break; 00114 case TargetParentOfSource: 00115 result_vec = source_to_top_vec; 00116 result_quat = source_to_top_quat; 00117 break; 00118 case SourceParentOfTarget: 00119 { 00120 btQuaternion inv_target_quat = target_to_top_quat.inverse(); 00121 btVector3 inv_target_vec = quatRotate(inv_target_quat, -target_to_top_vec); 00122 result_vec = inv_target_vec; 00123 result_quat = inv_target_quat; 00124 break; 00125 } 00126 case FullPath: 00127 { 00128 btQuaternion inv_target_quat = target_to_top_quat.inverse(); 00129 btVector3 inv_target_vec = quatRotate(inv_target_quat, -target_to_top_vec); 00130 00131 result_vec = quatRotate(inv_target_quat, source_to_top_vec) + inv_target_vec; 00132 result_quat = inv_target_quat * source_to_top_quat; 00133 } 00134 break; 00135 }; 00136 00137 time = _time; 00138 } 00139 00140 TransformStorage st; 00141 ros::Time time; 00142 btQuaternion source_to_top_quat; 00143 btVector3 source_to_top_vec; 00144 btQuaternion target_to_top_quat; 00145 btVector3 target_to_top_vec; 00146 00147 btQuaternion result_quat; 00148 btVector3 result_vec; 00149 }; 00150 00151 00152 std::string assert_resolved(const std::string& prefix, const std::string& frame_id) 00153 { 00154 if (frame_id.size() > 0) 00155 if (frame_id[0] != '/') 00156 ROS_DEBUG("TF operating on not fully resolved frame id %s, resolving using local prefix %s", frame_id.c_str(), prefix.c_str()); 00157 return tf::resolve(prefix, frame_id); 00158 }; 00159 00160 std::string tf::resolve(const std::string& prefix, const std::string& frame_name) 00161 { 00162 // printf ("resolveping prefix:%s with frame_name:%s\n", prefix.c_str(), frame_name.c_str()); 00163 if (frame_name.size() > 0) 00164 if (frame_name[0] == '/') 00165 { 00166 return frame_name; 00167 } 00168 if (prefix.size() > 0) 00169 { 00170 if (prefix[0] == '/') 00171 { 00172 std::string composite = prefix; 00173 composite.append("/"); 00174 composite.append(frame_name); 00175 return composite; 00176 } 00177 else 00178 { 00179 std::string composite; 00180 composite = "/"; 00181 composite.append(prefix); 00182 composite.append("/"); 00183 composite.append(frame_name); 00184 return composite; 00185 } 00186 00187 } 00188 else 00189 { 00190 std::string composite; 00191 composite = "/"; 00192 composite.append(frame_name); 00193 return composite; 00194 } 00195 }; 00196 00197 00198 00199 Transformer::Transformer(bool interpolating, 00200 ros::Duration cache_time): 00201 cache_time(cache_time), 00202 interpolating (interpolating), 00203 using_dedicated_thread_(false), 00204 fall_back_to_wall_time_(false) 00205 { 00206 max_extrapolation_distance_.fromNSec(DEFAULT_MAX_EXTRAPOLATION_DISTANCE); 00207 frameIDs_["NO_PARENT"] = 0; 00208 frames_.push_back(NULL);// new TimeCache(interpolating, cache_time, max_extrapolation_distance));//unused but needed for iteration over all elements 00209 frameIDs_reverse.push_back("NO_PARENT"); 00210 00211 return; 00212 } 00213 00214 Transformer::~Transformer() 00215 { 00216 /* deallocate all frames */ 00217 boost::recursive_mutex::scoped_lock lock(frame_mutex_); 00218 for (std::vector<TimeCache*>::iterator cache_it = frames_.begin(); cache_it != frames_.end(); ++cache_it) 00219 { 00220 delete (*cache_it); 00221 } 00222 00223 }; 00224 00225 00226 void Transformer::clear() 00227 { 00228 boost::recursive_mutex::scoped_lock lock(frame_mutex_); 00229 if ( frames_.size() > 1 ) 00230 { 00231 for (std::vector< TimeCache*>::iterator cache_it = frames_.begin() + 1; cache_it != frames_.end(); ++cache_it) 00232 { 00233 (*cache_it)->clearList(); 00234 } 00235 } 00236 } 00237 00238 00239 template<typename F> 00240 int Transformer::walkToTopParent(F& f, ros::Time time, CompactFrameID target_id, CompactFrameID source_id, std::string* error_string) const 00241 { 00242 // Short circuit if zero length transform to allow lookups on non existant links 00243 if (source_id == target_id) 00244 { 00245 f.finalize(Identity, time); 00246 return NO_ERROR; 00247 } 00248 00249 //If getting the latest get the latest common time 00250 if (time == ros::Time()) 00251 { 00252 int retval = getLatestCommonTime(target_id, source_id, time, error_string); 00253 if (retval != NO_ERROR) 00254 { 00255 return retval; 00256 } 00257 } 00258 00259 // Walk the tree to its root from the source frame, accumulating the transform 00260 CompactFrameID frame = source_id; 00261 CompactFrameID top_parent = frame; 00262 uint32_t depth = 0; 00263 while (frame != 0) 00264 { 00265 TimeCache* cache = getFrame(frame); 00266 00267 if (!cache) 00268 { 00269 // There will be no cache for the very root of the tree 00270 top_parent = frame; 00271 break; 00272 } 00273 00274 CompactFrameID parent = f.gather(cache, time, 0); 00275 if (parent == 0) 00276 { 00277 // Just break out here... there may still be a path from source -> target 00278 top_parent = frame; 00279 break; 00280 } 00281 00282 // Early out... target frame is a direct parent of the source frame 00283 if (frame == target_id) 00284 { 00285 f.finalize(TargetParentOfSource, time); 00286 return NO_ERROR; 00287 } 00288 00289 f.accum(true); 00290 00291 top_parent = frame; 00292 frame = parent; 00293 00294 ++depth; 00295 if (depth > MAX_GRAPH_DEPTH) 00296 { 00297 if (error_string) 00298 { 00299 std::stringstream ss; 00300 ss << "The tf tree is invalid because it contains a loop." << std::endl 00301 << allFramesAsString() << std::endl; 00302 *error_string = ss.str(); 00303 } 00304 return LOOKUP_ERROR; 00305 } 00306 } 00307 00308 // Now walk to the top parent from the target frame, accumulating its transform 00309 frame = target_id; 00310 depth = 0; 00311 while (frame != top_parent) 00312 { 00313 TimeCache* cache = getFrame(frame); 00314 00315 if (!cache) 00316 { 00317 break; 00318 } 00319 00320 CompactFrameID parent = f.gather(cache, time, error_string); 00321 if (parent == 0) 00322 { 00323 if (error_string) 00324 { 00325 std::stringstream ss; 00326 ss << *error_string << ", when looking up transform from frame [" << lookupFrameString(source_id) << "] to frame [" << lookupFrameString(target_id) << "]"; 00327 *error_string = ss.str(); 00328 } 00329 00330 return EXTRAPOLATION_ERROR; 00331 } 00332 00333 // Early out... source frame is a direct parent of the target frame 00334 if (frame == source_id) 00335 { 00336 f.finalize(SourceParentOfTarget, time); 00337 return NO_ERROR; 00338 } 00339 00340 f.accum(false); 00341 00342 frame = parent; 00343 00344 ++depth; 00345 if (depth > MAX_GRAPH_DEPTH) 00346 { 00347 if (error_string) 00348 { 00349 std::stringstream ss; 00350 ss << "The tf tree is invalid because it contains a loop." << std::endl 00351 << allFramesAsString() << std::endl; 00352 *error_string = ss.str(); 00353 } 00354 return LOOKUP_ERROR; 00355 } 00356 } 00357 00358 if (frame != top_parent) 00359 { 00360 createConnectivityErrorString(source_id, target_id, error_string); 00361 return CONNECTIVITY_ERROR; 00362 } 00363 00364 f.finalize(FullPath, time); 00365 00366 return NO_ERROR; 00367 } 00368 00369 00370 00371 bool Transformer::setTransform(const StampedTransform& transform, const std::string& authority) 00372 { 00373 00374 StampedTransform mapped_transform((btTransform)transform, transform.stamp_, transform.frame_id_, transform.child_frame_id_); 00375 mapped_transform.child_frame_id_ = assert_resolved(tf_prefix_, transform.child_frame_id_); 00376 mapped_transform.frame_id_ = assert_resolved(tf_prefix_, transform.frame_id_); 00377 00378 00379 bool error_exists = false; 00380 if (mapped_transform.child_frame_id_ == mapped_transform.frame_id_) 00381 { 00382 ROS_ERROR("TF_SELF_TRANSFORM: Ignoring transform from authority \"%s\" with frame_id and child_frame_id \"%s\" because they are the same", authority.c_str(), mapped_transform.child_frame_id_.c_str()); 00383 error_exists = true; 00384 } 00385 00386 if (mapped_transform.child_frame_id_ == "/")//empty frame id will be mapped to "/" 00387 { 00388 ROS_ERROR("TF_NO_CHILD_FRAME_ID: Ignoring transform from authority \"%s\" because child_frame_id not set ", authority.c_str()); 00389 error_exists = true; 00390 } 00391 00392 if (mapped_transform.frame_id_ == "/")//empty parent id will be mapped to "/" 00393 { 00394 ROS_ERROR("TF_NO_FRAME_ID: Ignoring transform with child_frame_id \"%s\" from authority \"%s\" because frame_id not set", mapped_transform.child_frame_id_.c_str(), authority.c_str()); 00395 error_exists = true; 00396 } 00397 00398 if (std::isnan(mapped_transform.getOrigin().x()) || std::isnan(mapped_transform.getOrigin().y()) || std::isnan(mapped_transform.getOrigin().z())|| 00399 std::isnan(mapped_transform.getRotation().x()) || std::isnan(mapped_transform.getRotation().y()) || std::isnan(mapped_transform.getRotation().z()) || std::isnan(mapped_transform.getRotation().w())) 00400 { 00401 ROS_ERROR("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)", 00402 mapped_transform.child_frame_id_.c_str(), authority.c_str(), 00403 mapped_transform.getOrigin().x(), mapped_transform.getOrigin().y(), mapped_transform.getOrigin().z(), 00404 mapped_transform.getRotation().x(), mapped_transform.getRotation().y(), mapped_transform.getRotation().z(), mapped_transform.getRotation().w() 00405 ); 00406 error_exists = true; 00407 } 00408 00409 if (error_exists) 00410 return false; 00411 00412 { 00413 boost::recursive_mutex::scoped_lock lock(frame_mutex_); 00414 CompactFrameID frame_number = lookupOrInsertFrameNumber(mapped_transform.child_frame_id_); 00415 TimeCache* frame = getFrame(frame_number); 00416 if (frame == NULL) 00417 { 00418 frames_[frame_number] = new TimeCache(cache_time); 00419 frame = frames_[frame_number]; 00420 } 00421 00422 if (frame->insertData(TransformStorage(mapped_transform, lookupOrInsertFrameNumber(mapped_transform.frame_id_), frame_number))) 00423 { 00424 frame_authority_[frame_number] = authority; 00425 } 00426 else 00427 { 00428 ROS_WARN("TF_OLD_DATA ignoring data from the past for frame %s at time %g according to authority %s\nPossible reasons are listed at ", mapped_transform.child_frame_id_.c_str(), mapped_transform.stamp_.toSec(), authority.c_str()); 00429 return false; 00430 } 00431 } 00432 00433 { 00434 boost::mutex::scoped_lock lock(transforms_changed_mutex_); 00435 transforms_changed_(); 00436 } 00437 00438 return true; 00439 }; 00440 00441 00442 void Transformer::lookupTransform(const std::string& target_frame, const std::string& source_frame, 00443 const ros::Time& time, StampedTransform& transform) const 00444 { 00445 std::string mapped_tgt = assert_resolved(tf_prefix_, target_frame); 00446 std::string mapped_src = assert_resolved(tf_prefix_, source_frame); 00447 00448 if (mapped_tgt == mapped_src) { 00449 transform.setIdentity(); 00450 transform.child_frame_id_ = mapped_src; 00451 transform.frame_id_ = mapped_tgt; 00452 transform.stamp_ = now(); 00453 return; 00454 } 00455 00456 boost::recursive_mutex::scoped_lock lock(frame_mutex_); 00457 00458 CompactFrameID target_id = lookupFrameNumber(mapped_tgt); 00459 CompactFrameID source_id = lookupFrameNumber(mapped_src); 00460 00461 std::string error_string; 00462 TransformAccum accum; 00463 int retval = walkToTopParent(accum, time, target_id, source_id, &error_string); 00464 if (retval != NO_ERROR) 00465 { 00466 switch (retval) 00467 { 00468 case CONNECTIVITY_ERROR: 00469 throw ConnectivityException(error_string); 00470 case EXTRAPOLATION_ERROR: 00471 throw ExtrapolationException(error_string); 00472 case LOOKUP_ERROR: 00473 throw LookupException(error_string); 00474 default: 00475 ROS_ERROR("Unknown error code: %d", retval); 00476 ROS_BREAK(); 00477 } 00478 } 00479 00480 transform.setOrigin(accum.result_vec); 00481 transform.setRotation(accum.result_quat); 00482 transform.child_frame_id_ = mapped_src; 00483 transform.frame_id_ = mapped_tgt; 00484 transform.stamp_ = accum.time; 00485 }; 00486 00487 00488 void Transformer::lookupTransform(const std::string& target_frame,const ros::Time& target_time, const std::string& source_frame, 00489 const ros::Time& source_time, const std::string& fixed_frame, StampedTransform& transform) const 00490 { 00491 tf::StampedTransform temp1, temp2; 00492 lookupTransform(fixed_frame, source_frame, source_time, temp1); 00493 lookupTransform(target_frame, fixed_frame, target_time, temp2); 00494 transform.setData( temp2 * temp1); 00495 transform.stamp_ = temp2.stamp_; 00496 transform.frame_id_ = target_frame; 00497 transform.child_frame_id_ = source_frame; 00498 00499 }; 00500 00501 00502 void Transformer::lookupTwist(const std::string& tracking_frame, const std::string& observation_frame, 00503 const ros::Time& time, const ros::Duration& averaging_interval, 00504 geometry_msgs::Twist& twist) const 00505 { 00506 lookupTwist(tracking_frame, observation_frame, observation_frame, tf::Point(0,0,0), tracking_frame, time, averaging_interval, twist); 00507 }; 00508 // ref point is origin of tracking_frame, ref_frame = obs_frame 00509 00510 00511 void Transformer::lookupTwist(const std::string& tracking_frame, const std::string& observation_frame, const std::string& reference_frame, 00512 const tf::Point & reference_point, const std::string& reference_point_frame, 00513 const ros::Time& time, const ros::Duration& averaging_interval, 00514 geometry_msgs::Twist& twist) const 00515 { 00516 ros::Time latest_time, target_time; 00517 getLatestCommonTime(observation_frame, tracking_frame, latest_time, NULL); 00518 00519 if (ros::Time() == time) 00520 target_time = latest_time; 00521 else 00522 target_time = time; 00523 00524 ros::Time end_time = std::min(target_time + averaging_interval *0.5 , latest_time); 00525 00526 ros::Time start_time = std::max(ros::Time().fromSec(.00001) + averaging_interval, end_time) - averaging_interval; // don't collide with zero 00527 ros::Duration corrected_averaging_interval = end_time - start_time; //correct for the possiblity that start time was truncated above. 00528 StampedTransform start, end; 00529 lookupTransform(observation_frame, tracking_frame, start_time, start); 00530 lookupTransform(observation_frame, tracking_frame, end_time, end); 00531 00532 00533 btMatrix3x3 temp = start.getBasis().inverse() * end.getBasis(); 00534 btQuaternion quat_temp; 00535 temp.getRotation(quat_temp); 00536 btVector3 o = start.getBasis() * quat_temp.getAxis(); 00537 btScalar ang = quat_temp.getAngle(); 00538 00539 double delta_x = end.getOrigin().getX() - start.getOrigin().getX(); 00540 double delta_y = end.getOrigin().getY() - start.getOrigin().getY(); 00541 double delta_z = end.getOrigin().getZ() - start.getOrigin().getZ(); 00542 00543 00544 btVector3 twist_vel ((delta_x)/corrected_averaging_interval.toSec(), 00545 (delta_y)/corrected_averaging_interval.toSec(), 00546 (delta_z)/corrected_averaging_interval.toSec()); 00547 btVector3 twist_rot = o * (ang / corrected_averaging_interval.toSec()); 00548 00549 00550 // This is a twist w/ reference frame in observation_frame and reference point is in the tracking_frame at the origin (at start_time) 00551 00552 00553 //correct for the position of the reference frame 00554 tf::StampedTransform inverse; 00555 lookupTransform(reference_frame,tracking_frame, target_time, inverse); 00556 btVector3 out_rot = inverse.getBasis() * twist_rot; 00557 btVector3 out_vel = inverse.getBasis()* twist_vel + inverse.getOrigin().cross(out_rot); 00558 00559 00560 //Rereference the twist about a new reference point 00561 // Start by computing the original reference point in the reference frame: 00562 tf::Stamped<tf::Point> rp_orig(tf::Point(0,0,0), target_time, tracking_frame); 00563 transformPoint(reference_frame, rp_orig, rp_orig); 00564 // convert the requrested reference point into the right frame 00565 tf::Stamped<tf::Point> rp_desired(reference_point, target_time, reference_point_frame); 00566 transformPoint(reference_frame, rp_desired, rp_desired); 00567 // compute the delta 00568 tf::Point delta = rp_desired - rp_orig; 00569 // Correct for the change in reference point 00570 out_vel = out_vel + out_rot * delta; 00571 // out_rot unchanged 00572 00573 /* 00574 printf("KDL: Rotation %f %f %f, Translation:%f %f %f\n", 00575 out_rot.x(),out_rot.y(),out_rot.z(), 00576 out_vel.x(),out_vel.y(),out_vel.z()); 00577 */ 00578 00579 twist.linear.x = out_vel.x(); 00580 twist.linear.y = out_vel.y(); 00581 twist.linear.z = out_vel.z(); 00582 twist.angular.x = out_rot.x(); 00583 twist.angular.y = out_rot.y(); 00584 twist.angular.z = out_rot.z(); 00585 00586 }; 00587 00588 bool Transformer::waitForTransform(const std::string& target_frame, const std::string& source_frame, 00589 const ros::Time& time, 00590 const ros::Duration& timeout, const ros::Duration& polling_sleep_duration, 00591 std::string* error_msg) const 00592 { 00593 if (!using_dedicated_thread_) 00594 { 00595 std::string error_string = "Do not call waitForTransform unless you are using another thread for populating data. Without a dedicated thread it will always timeout. If you have a seperate thread servicing tf messages, call setUsingDedicatedThread(true)"; 00596 ROS_ERROR("%s",error_string.c_str()); 00597 00598 if (error_msg) 00599 *error_msg = error_string; 00600 return false; 00601 } 00602 ros::Time start_time = now(); 00603 std::string mapped_tgt = assert_resolved(tf_prefix_, target_frame); 00604 std::string mapped_src = assert_resolved(tf_prefix_, source_frame); 00605 00606 while (ok() && (now() - start_time) < timeout) 00607 { 00608 if (frameExists(mapped_tgt) && frameExists(mapped_src) && (canTransform(mapped_tgt, mapped_src, time, error_msg))) 00609 return true; 00610 00611 usleep(polling_sleep_duration.sec * 1000000 + polling_sleep_duration.nsec / 1000); //hack to avoid calling ros::Time::now() in Duration.sleep 00612 } 00613 return false; 00614 } 00615 00616 bool Transformer::canTransformNoLock(CompactFrameID target_id, CompactFrameID source_id, 00617 const ros::Time& time, std::string* error_msg) const 00618 { 00619 if (target_id == 0 || source_id == 0) 00620 { 00621 return false; 00622 } 00623 00624 CanTransformAccum accum; 00625 if (walkToTopParent(accum, time, target_id, source_id, error_msg) == NO_ERROR) 00626 { 00627 return true; 00628 } 00629 00630 return false; 00631 } 00632 00633 bool Transformer::canTransformInternal(CompactFrameID target_id, CompactFrameID source_id, 00634 const ros::Time& time, std::string* error_msg) const 00635 { 00636 boost::recursive_mutex::scoped_lock lock(frame_mutex_); 00637 return canTransformNoLock(target_id, source_id, time, error_msg); 00638 } 00639 00640 bool Transformer::canTransform(const std::string& target_frame, const std::string& source_frame, 00641 const ros::Time& time, std::string* error_msg) const 00642 { 00643 std::string mapped_tgt = assert_resolved(tf_prefix_, target_frame); 00644 std::string mapped_src = assert_resolved(tf_prefix_, source_frame); 00645 00646 if (mapped_tgt == mapped_src) 00647 return true; 00648 00649 boost::recursive_mutex::scoped_lock lock(frame_mutex_); 00650 00651 if (!frameExists(mapped_tgt) || !frameExists(mapped_src)) 00652 return false; 00653 00654 CompactFrameID target_id = lookupFrameNumber(mapped_tgt); 00655 CompactFrameID source_id = lookupFrameNumber(mapped_src); 00656 00657 return canTransformNoLock(target_id, source_id, time, error_msg); 00658 } 00659 00660 00661 00662 bool Transformer::canTransform(const std::string& target_frame,const ros::Time& target_time, const std::string& source_frame, 00663 const ros::Time& source_time, const std::string& fixed_frame, 00664 std::string* error_msg) const 00665 { 00666 return canTransform(target_frame, fixed_frame, target_time) && canTransform(fixed_frame, source_frame, source_time, error_msg); 00667 }; 00668 00669 bool Transformer::waitForTransform(const std::string& target_frame,const ros::Time& target_time, const std::string& source_frame, 00670 const ros::Time& source_time, const std::string& fixed_frame, 00671 const ros::Duration& timeout, const ros::Duration& polling_sleep_duration, 00672 std::string* error_msg) const 00673 { 00674 return waitForTransform(target_frame, fixed_frame, target_time, timeout, polling_sleep_duration, error_msg) && waitForTransform(fixed_frame, source_frame, source_time, timeout, polling_sleep_duration, error_msg); 00675 }; 00676 00677 00678 bool Transformer::getParent(const std::string& frame_id, ros::Time time, std::string& parent) const 00679 { 00680 std::string mapped_frame_id = assert_resolved(tf_prefix_, frame_id); 00681 tf::TimeCache* cache; 00682 try 00683 { 00684 cache = getFrame(lookupFrameNumber(mapped_frame_id)); 00685 } 00686 catch (tf::LookupException &ex) 00687 { 00688 ROS_ERROR("Transformer::getParent: %s",ex.what()); 00689 return false; 00690 } 00691 00692 TransformStorage temp; 00693 if (! cache->getData(time, temp)) { 00694 ROS_DEBUG("Transformer::getParent: No data for parent of %s", mapped_frame_id.c_str()); 00695 return false; 00696 } 00697 if (temp.frame_id_ == 0) { 00698 ROS_DEBUG("Transformer::getParent: No parent for %s", mapped_frame_id.c_str()); 00699 return false; 00700 } 00701 00702 parent = lookupFrameString(temp.frame_id_); 00703 return true; 00704 }; 00705 00706 00707 bool Transformer::frameExists(const std::string& frame_id_str) const 00708 { 00709 boost::recursive_mutex::scoped_lock lock(frame_mutex_); 00710 std::string frame_id_resolveped = assert_resolved(tf_prefix_, frame_id_str); 00711 00712 return frameIDs_.count(frame_id_resolveped); 00713 } 00714 00715 void Transformer::setExtrapolationLimit(const ros::Duration& distance) 00716 { 00717 max_extrapolation_distance_ = distance; 00718 } 00719 00720 void Transformer::createConnectivityErrorString(CompactFrameID source_frame, CompactFrameID target_frame, std::string* out) const 00721 { 00722 if (!out) 00723 { 00724 return; 00725 } 00726 *out = std::string("Could not find a connection between '"+lookupFrameString(target_frame)+"' and '"+ 00727 lookupFrameString(source_frame)+"' because they are not part of the same tree."+ 00728 "Tf has two or more unconnected trees."); 00729 } 00730 00731 struct TimeAndFrameIDFrameComparator 00732 { 00733 TimeAndFrameIDFrameComparator(CompactFrameID id) 00734 : id(id) 00735 {} 00736 00737 bool operator()(const P_TimeAndFrameID& rhs) const 00738 { 00739 return rhs.second == id; 00740 } 00741 00742 CompactFrameID id; 00743 }; 00744 00745 int Transformer::getLatestCommonTime(const std::string &source_frame, const std::string &target_frame, ros::Time& time, std::string* error_string) const 00746 { 00747 std::string mapped_tgt = assert_resolved(tf_prefix_, target_frame); 00748 std::string mapped_src = assert_resolved(tf_prefix_, source_frame); 00749 00750 if (!frameExists(mapped_tgt) || !frameExists(mapped_src)) { 00751 time = ros::Time(); 00752 return LOOKUP_ERROR; 00753 } 00754 00755 CompactFrameID source_id = lookupFrameNumber(mapped_src); 00756 CompactFrameID target_id = lookupFrameNumber(mapped_tgt); 00757 return getLatestCommonTime(source_id, target_id, time, error_string); 00758 } 00759 00760 00761 int Transformer::getLatestCommonTime(CompactFrameID target_id, CompactFrameID source_id, ros::Time & time, std::string * error_string) const 00762 { 00763 if (source_id == target_id) 00764 { 00765 //Set time to latest timestamp of frameid in case of target and source frame id are the same 00766 time = now(); 00767 return NO_ERROR; 00768 } 00769 00770 std::vector<P_TimeAndFrameID> lct_cache; 00771 00772 // Walk the tree to its root from the source frame, accumulating the list of parent/time as well as the latest time 00773 // in the target is a direct parent 00774 CompactFrameID frame = source_id; 00775 P_TimeAndFrameID temp; 00776 uint32_t depth = 0; 00777 ros::Time common_time = ros::TIME_MAX; 00778 while (frame != 0) 00779 { 00780 TimeCache* cache = getFrame(frame); 00781 00782 if (!cache) 00783 { 00784 // There will be no cache for the very root of the tree 00785 break; 00786 } 00787 00788 P_TimeAndFrameID latest = cache->getLatestTimeAndParent(); 00789 00790 if (latest.second == 0) 00791 { 00792 // Just break out here... there may still be a path from source -> target 00793 break; 00794 } 00795 00796 if (!latest.first.isZero()) 00797 { 00798 common_time = std::min(latest.first, common_time); 00799 } 00800 00801 lct_cache.push_back(latest); 00802 00803 frame = latest.second; 00804 00805 // Early out... target frame is a direct parent of the source frame 00806 if (frame == target_id) 00807 { 00808 time = common_time; 00809 if (time == ros::TIME_MAX) 00810 { 00811 time = ros::Time(); 00812 } 00813 return NO_ERROR; 00814 } 00815 00816 ++depth; 00817 if (depth > MAX_GRAPH_DEPTH) 00818 { 00819 if (error_string) 00820 { 00821 std::stringstream ss; 00822 ss<<"The tf tree is invalid because it contains a loop." << std::endl 00823 << allFramesAsString() << std::endl; 00824 *error_string = ss.str(); 00825 } 00826 return LOOKUP_ERROR; 00827 } 00828 } 00829 00830 // Now walk to the top parent from the target frame, accumulating the latest time and looking for a common parent 00831 frame = target_id; 00832 depth = 0; 00833 common_time = ros::TIME_MAX; 00834 CompactFrameID common_parent = 0; 00835 while (true) 00836 { 00837 TimeCache* cache = getFrame(frame); 00838 00839 if (!cache) 00840 { 00841 break; 00842 } 00843 00844 P_TimeAndFrameID latest = cache->getLatestTimeAndParent(); 00845 00846 if (latest.second == 0) 00847 { 00848 break; 00849 } 00850 00851 if (!latest.first.isZero()) 00852 { 00853 common_time = std::min(latest.first, common_time); 00854 } 00855 00856 std::vector<P_TimeAndFrameID>::iterator it = std::find_if(lct_cache.begin(), lct_cache.end(), TimeAndFrameIDFrameComparator(latest.second)); 00857 if (it != lct_cache.end()) // found a common parent 00858 { 00859 common_parent = it->second; 00860 break; 00861 } 00862 00863 frame = latest.second; 00864 00865 // Early out... source frame is a direct parent of the target frame 00866 if (frame == source_id) 00867 { 00868 time = common_time; 00869 if (time == ros::TIME_MAX) 00870 { 00871 time = ros::Time(); 00872 } 00873 return NO_ERROR; 00874 } 00875 00876 ++depth; 00877 if (depth > MAX_GRAPH_DEPTH) 00878 { 00879 if (error_string) 00880 { 00881 std::stringstream ss; 00882 ss<<"The tf tree is invalid because it contains a loop." << std::endl 00883 << allFramesAsString() << std::endl; 00884 *error_string = ss.str(); 00885 } 00886 return LOOKUP_ERROR; 00887 } 00888 } 00889 00890 if (common_parent == 0) 00891 { 00892 createConnectivityErrorString(source_id, target_id, error_string); 00893 return CONNECTIVITY_ERROR; 00894 } 00895 00896 // Loop through the source -> root list until we hit the common parent 00897 { 00898 std::vector<P_TimeAndFrameID>::iterator it = lct_cache.begin(); 00899 std::vector<P_TimeAndFrameID>::iterator end = lct_cache.end(); 00900 for (; it != end; ++it) 00901 { 00902 if (!it->first.isZero()) 00903 { 00904 common_time = std::min(common_time, it->first); 00905 } 00906 00907 if (it->second == common_parent) 00908 { 00909 break; 00910 } 00911 } 00912 } 00913 00914 if (common_time == ros::TIME_MAX) 00915 { 00916 common_time = ros::Time(); 00917 } 00918 00919 time = common_time; 00920 return NO_ERROR; 00921 } 00922 00923 00924 00925 /* 00926 int Transformer::lookupLists(unsigned int target_frame, ros::Time time, unsigned int source_frame, TransformLists& lists, std::string * error_string) const 00927 { 00929 00930 //Clear lists before operating 00931 lists.forwardTransforms.clear(); 00932 lists.inverseTransforms.clear(); 00933 // TransformLists mTfLs; 00934 if (target_frame == source_frame) 00935 return 0; //Don't do anythign if we're not going anywhere 00936 00937 TransformStorage temp; 00938 00939 unsigned int frame = source_frame; 00940 unsigned int counter = 0; //A counter to keep track of how deep we've descended 00941 unsigned int last_inverse; 00942 if (getFrame(frame) == NULL) //Test if source frame exists this will throw a lookup error if it does not (inside the loop it will be caught) 00943 { 00944 if (error_string) *error_string = "Source frame '"+lookupFrameString(frame)+"' does not exist is tf tree."; 00945 return LOOKUP_ERROR;//throw LookupException("Frame didn't exist"); 00946 } 00947 while (true) 00948 { 00949 // printf("getting data from %d:%s \n", frame, lookupFrameString(frame).c_str()); 00950 00951 TimeCache* pointer = getFrame(frame); 00952 ROS_ASSERT(pointer); 00953 00954 if (! pointer->getData(time, temp)) 00955 { 00956 last_inverse = frame; 00957 // this is thrown when there is no data 00958 break; 00959 } 00960 00961 //break if parent is NO_PARENT (0) 00962 if (frame == 0) 00963 { 00964 last_inverse = frame; 00965 break; 00966 } 00967 lists.inverseTransforms.push_back(temp); 00968 00969 frame = temp.frame_id_num_; 00970 00971 00972 // Check if we've gone too deep. A loop in the tree would cause this 00973 if (counter++ > MAX_GRAPH_DEPTH) 00974 { 00975 if (error_string) 00976 { 00977 std::stringstream ss; 00978 ss<<"The tf tree is invalid because it contains a loop." << std::endl 00979 << allFramesAsString() << std::endl; 00980 *error_string =ss.str(); 00981 } 00982 return LOOKUP_ERROR; 00983 // throw(LookupException(ss.str())); 00984 } 00985 } 00986 00987 frame = target_frame; 00988 counter = 0; 00989 unsigned int last_forward; 00990 if (getFrame(frame) == NULL) 00991 { 00992 if (error_string) *error_string = "Target frame '"+lookupFrameString(frame)+"' does not exist is tf tree."; 00993 return LOOKUP_ERROR; 00994 }//throw LookupException("fixme");; //Test if source frame exists this will throw a lookup error if it does not (inside the loop it will be caught) 00995 while (true) 00996 { 00997 00998 TimeCache* pointer = getFrame(frame); 00999 ROS_ASSERT(pointer); 01000 01001 01002 if(! pointer->getData(time, temp)) 01003 { 01004 last_forward = frame; 01005 break; 01006 } 01007 01008 //break if parent is NO_PARENT (0) 01009 if (frame == 0) 01010 { 01011 last_forward = frame; 01012 break; 01013 } 01014 // std::cout << "pushing back" << temp.frame_id_ << std::endl; 01015 lists.forwardTransforms.push_back(temp); 01016 frame = temp.frame_id_num_; 01017 01018 // Check if we've gone too deep. A loop in the tree would cause this 01019 if (counter++ > MAX_GRAPH_DEPTH){ 01020 if (error_string) 01021 { 01022 std::stringstream ss; 01023 ss<<"The tf tree is invalid because it contains a loop." << std::endl 01024 << allFramesAsString() << std::endl; 01025 *error_string = ss.str(); 01026 } 01027 return LOOKUP_ERROR;//throw(LookupException(ss.str())); 01028 } 01029 } 01030 01031 std::string connectivity_error("Could not find a connection between '"+lookupFrameString(target_frame)+"' and '"+ 01032 lookupFrameString(source_frame)+"' because they are not part of the same tree."+ 01033 "Tf has two or more unconnected trees."); 01034 // Check the zero length cases 01035 if (lists.inverseTransforms.size() == 0) 01036 { 01037 if (lists.forwardTransforms.size() == 0) //If it's going to itself it's already been caught 01038 { 01039 if (error_string) *error_string = connectivity_error; 01040 return CONNECTIVITY_ERROR; 01041 } 01042 01043 if (last_forward != source_frame) //\todo match with case A 01044 { 01045 if (error_string) *error_string = connectivity_error; 01046 return CONNECTIVITY_ERROR; 01047 } 01048 else return 0; 01049 } 01050 01051 if (lists.forwardTransforms.size() == 0) 01052 { 01053 if (lists.inverseTransforms.size() == 0) //If it's going to itself it's already been caught 01054 {//\todo remove THis is the same as case D 01055 if (error_string) *error_string = connectivity_error; 01056 return CONNECTIVITY_ERROR; 01057 } 01058 01059 try 01060 { 01061 if (lookupFrameNumber(lists.inverseTransforms.back().frame_id_) != target_frame) 01062 { 01063 if (error_string) *error_string = connectivity_error; 01064 return CONNECTIVITY_ERROR; 01065 } 01066 else return 0; 01067 } 01068 catch (tf::LookupException & ex) 01069 { 01070 if (error_string) *error_string = ex.what(); 01071 return LOOKUP_ERROR; 01072 } 01073 } 01074 01075 01076 // Make sure the end of the search shares a parent. 01077 if (last_forward != last_inverse) 01078 { 01079 if (error_string) *error_string = connectivity_error; 01080 return CONNECTIVITY_ERROR; 01081 } 01082 // Make sure that we don't have a no parent at the top 01083 try 01084 { 01085 if (lookupFrameNumber(lists.inverseTransforms.back().child_frame_id_) == 0 || lookupFrameNumber( lists.forwardTransforms.back().child_frame_id_) == 0) 01086 { 01087 //if (error_string) *error_string = "NO_PARENT at top of tree"; 01088 if (error_string) *error_string = connectivity_error; 01089 return CONNECTIVITY_ERROR; 01090 } 01091 01092 while (lookupFrameNumber(lists.inverseTransforms.back().child_frame_id_) == lookupFrameNumber(lists.forwardTransforms.back().child_frame_id_)) 01093 { 01094 lists.inverseTransforms.pop_back(); 01095 lists.forwardTransforms.pop_back(); 01096 01097 // Make sure we don't go beyond the beginning of the list. 01098 // (The while statement above doesn't fail if you hit the beginning of the list, 01099 // which happens in the zero distance case.) 01100 if (lists.inverseTransforms.size() == 0 || lists.forwardTransforms.size() == 0) 01101 break; 01102 } 01103 } 01104 catch (tf::LookupException & ex) 01105 { 01106 if (error_string) *error_string = ex.what(); 01107 return LOOKUP_ERROR; 01108 } 01109 return 0; 01110 01111 } 01112 */ 01113 01114 /* 01115 bool Transformer::test_extrapolation_one_value(const ros::Time& target_time, const TransformStorage& tr, std::string* error_string) const 01116 { 01117 std::stringstream ss; 01118 ss << std::fixed; 01119 ss.precision(3); 01120 01121 if (tr.mode_ == ONE_VALUE) 01122 { 01123 if (tr.stamp_ - target_time > max_extrapolation_distance_ || target_time - tr.stamp_ > max_extrapolation_distance_) 01124 { 01125 if (error_string) { 01126 ss << "You requested a transform at time " << (target_time).toSec() 01127 << ",\n but the tf buffer only contains a single transform " 01128 << "at time " << tr.stamp_.toSec() << ".\n"; 01129 if ( max_extrapolation_distance_ > ros::Duration(0)) 01130 { 01131 ss << "The tf extrapollation distance is set to " 01132 << (max_extrapolation_distance_).toSec() <<" seconds.\n"; 01133 } 01134 *error_string = ss.str(); 01135 } 01136 return true; 01137 } 01138 } 01139 return false; 01140 } 01141 01142 01143 bool Transformer::test_extrapolation_past(const ros::Time& target_time, const TransformStorage& tr, std::string* error_string) const 01144 { 01145 std::stringstream ss; 01146 ss << std::fixed; 01147 ss.precision(3); 01148 01149 if (tr.mode_ == EXTRAPOLATE_BACK && tr.stamp_ - target_time > max_extrapolation_distance_) 01150 { 01151 if (error_string) { 01152 ss << "You requested a transform that is " << (now() - target_time).toSec() << " seconds in the past, \n" 01153 << "but the tf buffer only has a history of " << (now() - tr.stamp_).toSec() << " seconds.\n"; 01154 if ( max_extrapolation_distance_ > ros::Duration(0)) 01155 { 01156 ss << "The tf extrapollation distance is set to " 01157 << (max_extrapolation_distance_).toSec() <<" seconds.\n"; 01158 } 01159 *error_string = ss.str(); 01160 } 01161 return true; 01162 } 01163 return false; 01164 } 01165 01166 01167 bool Transformer::test_extrapolation_future(const ros::Time& target_time, const TransformStorage& tr, std::string* error_string) const 01168 { 01169 std::stringstream ss; 01170 ss << std::fixed; 01171 ss.precision(3); 01172 01173 if( tr.mode_ == EXTRAPOLATE_FORWARD && target_time - tr.stamp_ > max_extrapolation_distance_) 01174 { 01175 if (error_string){ 01176 ss << "You requested a transform that is " << (now() - target_time).toSec()*1000 << " miliseconds in the past, \n" 01177 << "but the most recent transform in the tf buffer is " << (now() - tr.stamp_).toSec()*1000 << " miliseconds old.\n"; 01178 if ( max_extrapolation_distance_ > ros::Duration(0)) 01179 { 01180 ss << "The tf extrapollation distance is set to " 01181 << (max_extrapolation_distance_).toSec() <<" seconds.\n"; 01182 } 01183 *error_string = ss.str(); 01184 } 01185 return true; 01186 } 01187 return false; 01188 } 01189 01190 01191 bool Transformer::test_extrapolation(const ros::Time& target_time, const TransformLists& lists, std::string * error_string) const 01192 { 01193 std::stringstream ss; 01194 ss << std::fixed; 01195 ss.precision(3); 01196 for (unsigned int i = 0; i < lists.inverseTransforms.size(); i++) 01197 { 01198 if (test_extrapolation_one_value(target_time, lists.inverseTransforms[i], error_string)) return true; 01199 if (test_extrapolation_past(target_time, lists.inverseTransforms[i], error_string)) return true; 01200 if (test_extrapolation_future(target_time, lists.inverseTransforms[i], error_string)) return true; 01201 } 01202 01203 for (unsigned int i = 0; i < lists.forwardTransforms.size(); i++) 01204 { 01205 if (test_extrapolation_one_value(target_time, lists.forwardTransforms[i], error_string)) return true; 01206 if (test_extrapolation_past(target_time, lists.forwardTransforms[i], error_string)) return true; 01207 if (test_extrapolation_future(target_time, lists.forwardTransforms[i], error_string)) return true; 01208 } 01209 01210 return false; 01211 } 01212 */ 01213 01214 01215 01216 /* 01217 std::string Transformer::chainAsString(const std::string & target_frame, ros::Time target_time, const std::string & source_frame, ros::Time source_time, const std::string& fixed_frame) const 01218 { 01219 std::string error_string; 01220 std::stringstream mstream; 01221 TransformLists lists; 01223 try 01224 { 01225 lookupLists(lookupFrameNumber(target_frame), target_time, lookupFrameNumber(source_frame), lists, &error_string); 01226 } 01227 catch (tf::LookupException &ex) 01228 { 01229 mstream << ex.what(); 01230 return mstream.str(); 01231 } 01232 mstream << "Inverse Transforms:" <<std::endl; 01233 for (unsigned int i = 0; i < lists.inverseTransforms.size(); i++) 01234 { 01235 mstream << lists.inverseTransforms[i].child_frame_id_<<", "; 01236 } 01237 mstream << std::endl; 01238 01239 mstream << "Forward Transforms: "<<std::endl ; 01240 for (unsigned int i = 0; i < lists.forwardTransforms.size(); i++) 01241 { 01242 mstream << lists.forwardTransforms[i].child_frame_id_<<", "; 01243 } 01244 mstream << std::endl; 01245 return mstream.str(); 01246 } 01247 */ 01248 01249 //@todo - Fix this to work with new data structures 01250 void Transformer::chainAsVector(const std::string & target_frame, ros::Time target_time, const std::string & source_frame, ros::Time source_time, const std::string& fixed_frame, std::vector<std::string>& output) const 01251 { 01252 std::string error_string; 01253 01254 output.clear(); //empty vector 01255 01256 std::stringstream mstream; 01257 boost::recursive_mutex::scoped_lock lock(frame_mutex_); 01258 01259 TransformStorage temp; 01260 01262 for (unsigned int counter = 1; counter < frames_.size(); counter ++) 01263 { 01264 TimeCache* frame_ptr = getFrame(CompactFrameID(counter)); 01265 if (frame_ptr == NULL) 01266 continue; 01267 CompactFrameID frame_id_num; 01268 if (frame_ptr->getData(ros::Time(), temp)) 01269 frame_id_num = temp.frame_id_; 01270 else 01271 { 01272 frame_id_num = 0; 01273 } 01274 output.push_back(frameIDs_reverse[frame_id_num]); 01275 } 01276 } 01277 01278 std::string Transformer::allFramesAsString() const 01279 { 01280 std::stringstream mstream; 01281 boost::recursive_mutex::scoped_lock lock(frame_mutex_); 01282 01283 TransformStorage temp; 01284 01286 for (unsigned int counter = 1; counter < frames_.size(); counter ++) 01287 { 01288 TimeCache* frame_ptr = getFrame(CompactFrameID(counter)); 01289 if (frame_ptr == NULL) 01290 continue; 01291 CompactFrameID frame_id_num; 01292 if( frame_ptr->getData(ros::Time(), temp)) 01293 frame_id_num = temp.frame_id_; 01294 else 01295 { 01296 frame_id_num = 0; 01297 } 01298 mstream << "Frame "<< frameIDs_reverse[counter] << " exists with parent " << frameIDs_reverse[frame_id_num] << "." <<std::endl; 01299 } 01300 01301 return mstream.str(); 01302 } 01303 01304 std::string Transformer::allFramesAsDot() const 01305 { 01306 std::stringstream mstream; 01307 mstream << "digraph G {" << std::endl; 01308 boost::recursive_mutex::scoped_lock lock(frame_mutex_); 01309 01310 TransformStorage temp; 01311 01312 ros::Time current_time = now(); 01313 01314 if (frames_.size() ==1) 01315 mstream <<"\"no tf data recieved\""; 01316 01317 mstream.precision(3); 01318 mstream.setf(std::ios::fixed,std::ios::floatfield); 01319 01320 // for (std::vector< TimeCache*>::iterator it = frames_.begin(); it != frames_.end(); ++it) 01321 for (unsigned int counter = 1; counter < frames_.size(); counter ++)//one referenced for 0 is no frame 01322 { 01323 unsigned int frame_id_num; 01324 if( getFrame(counter)->getData(ros::Time(), temp)) 01325 frame_id_num = temp.frame_id_; 01326 else 01327 { 01328 frame_id_num = 0; 01329 } 01330 if (frame_id_num != 0) 01331 { 01332 std::string authority = "no recorded authority"; 01333 std::map<unsigned int, std::string>::const_iterator it = frame_authority_.find(counter); 01334 if (it != frame_authority_.end()) 01335 authority = it->second; 01336 01337 double rate = getFrame(counter)->getListLength() / std::max((getFrame(counter)->getLatestTimestamp().toSec() - 01338 getFrame(counter)->getOldestTimestamp().toSec() ), 0.0001); 01339 01340 mstream << std::fixed; //fixed point notation 01341 mstream.precision(3); //3 decimal places 01342 mstream << "\"" << frameIDs_reverse[frame_id_num] << "\"" << " -> " 01343 << "\"" << frameIDs_reverse[counter] << "\"" << "[label=\"" 01344 //<< "Time: " << current_time.toSec() << "\\n" 01345 << "Broadcaster: " << authority << "\\n" 01346 << "Average rate: " << rate << " Hz\\n" 01347 << "Most recent transform: " << (current_time - getFrame(counter)->getLatestTimestamp()).toSec() << " sec old \\n" 01348 // << "(time: " << getFrame(counter)->getLatestTimestamp().toSec() << ")\\n" 01349 // << "Oldest transform: " << (current_time - getFrame(counter)->getOldestTimestamp()).toSec() << " sec old \\n" 01350 // << "(time: " << (getFrame(counter)->getOldestTimestamp()).toSec() << ")\\n" 01351 << "Buffer length: " << (getFrame(counter)->getLatestTimestamp()-getFrame(counter)->getOldestTimestamp()).toSec() << " sec\\n" 01352 <<"\"];" <<std::endl; 01353 } 01354 } 01355 01356 for (unsigned int counter = 1; counter < frames_.size(); counter ++)//one referenced for 0 is no frame 01357 { 01358 unsigned int frame_id_num; 01359 if( getFrame(counter)->getData(ros::Time(), temp)) 01360 frame_id_num = temp.frame_id_; 01361 else 01362 { 01363 frame_id_num = 0; 01364 } 01365 01366 if(frameIDs_reverse[frame_id_num]=="NO_PARENT") 01367 { 01368 mstream << "edge [style=invis];" <<std::endl; 01369 mstream << " subgraph cluster_legend { style=bold; color=black; label =\"view_frames Result\";\n" 01370 << "\"Recorded at time: " << current_time.toSec() << "\"[ shape=plaintext ] ;\n " 01371 << "}" << "->" << "\"" << frameIDs_reverse[counter]<<"\";" <<std::endl; 01372 } 01373 } 01374 mstream << "}"; 01375 return mstream.str(); 01376 } 01377 01378 01379 bool Transformer::ok() const { return true; } 01380 01381 void Transformer::getFrameStrings(std::vector<std::string> & vec) const 01382 { 01383 vec.clear(); 01384 01385 boost::recursive_mutex::scoped_lock lock(frame_mutex_); 01386 01387 TransformStorage temp; 01388 01389 // for (std::vector< TimeCache*>::iterator it = frames_.begin(); it != frames_.end(); ++it) 01390 for (unsigned int counter = 1; counter < frames_.size(); counter ++) 01391 { 01392 vec.push_back(frameIDs_reverse[counter]); 01393 } 01394 return; 01395 } 01396 01397 tf::TimeCache* Transformer::getFrame(unsigned int frame_id) const 01398 { 01399 if (frame_id == 0) 01400 return NULL; 01401 else 01402 return frames_[frame_id]; 01403 }; 01404 01405 01406 void Transformer::transformQuaternion(const std::string& target_frame, const Stamped<Quaternion>& stamped_in, Stamped<Quaternion>& stamped_out) const 01407 { 01408 tf::assertQuaternionValid(stamped_in); 01409 01410 StampedTransform transform; 01411 lookupTransform(target_frame, stamped_in.frame_id_, stamped_in.stamp_, transform); 01412 01413 stamped_out.setData( transform * stamped_in); 01414 stamped_out.stamp_ = transform.stamp_; 01415 stamped_out.frame_id_ = target_frame; 01416 }; 01417 01418 01419 void Transformer::transformVector(const std::string& target_frame, 01420 const Stamped<tf::Vector3>& stamped_in, 01421 Stamped<tf::Vector3>& stamped_out) const 01422 { 01423 StampedTransform transform; 01424 lookupTransform(target_frame, stamped_in.frame_id_, stamped_in.stamp_, transform); 01425 01427 btVector3 end = stamped_in; 01428 btVector3 origin = btVector3(0,0,0); 01429 btVector3 output = (transform * end) - (transform * origin); 01430 stamped_out.setData( output); 01431 01432 stamped_out.stamp_ = transform.stamp_; 01433 stamped_out.frame_id_ = target_frame; 01434 }; 01435 01436 01437 void Transformer::transformPoint(const std::string& target_frame, const Stamped<Point>& stamped_in, Stamped<Point>& stamped_out) const 01438 { 01439 StampedTransform transform; 01440 lookupTransform(target_frame, stamped_in.frame_id_, stamped_in.stamp_, transform); 01441 01442 stamped_out.setData(transform * stamped_in); 01443 stamped_out.stamp_ = transform.stamp_; 01444 stamped_out.frame_id_ = target_frame; 01445 }; 01446 01447 void Transformer::transformPose(const std::string& target_frame, const Stamped<Pose>& stamped_in, Stamped<Pose>& stamped_out) const 01448 { 01449 StampedTransform transform; 01450 lookupTransform(target_frame, stamped_in.frame_id_, stamped_in.stamp_, transform); 01451 01452 stamped_out.setData(transform * stamped_in); 01453 stamped_out.stamp_ = transform.stamp_; 01454 stamped_out.frame_id_ = target_frame; 01455 }; 01456 01457 01458 void Transformer::transformQuaternion(const std::string& target_frame, const ros::Time& target_time, 01459 const Stamped<Quaternion>& stamped_in, 01460 const std::string& fixed_frame, 01461 Stamped<Quaternion>& stamped_out) const 01462 { 01463 tf::assertQuaternionValid(stamped_in); 01464 StampedTransform transform; 01465 lookupTransform(target_frame, target_time, 01466 stamped_in.frame_id_,stamped_in.stamp_, 01467 fixed_frame, transform); 01468 01469 stamped_out.setData( transform * stamped_in); 01470 stamped_out.stamp_ = transform.stamp_; 01471 stamped_out.frame_id_ = target_frame; 01472 }; 01473 01474 01475 void Transformer::transformVector(const std::string& target_frame, const ros::Time& target_time, 01476 const Stamped<Vector3>& stamped_in, 01477 const std::string& fixed_frame, 01478 Stamped<Vector3>& stamped_out) const 01479 { 01480 StampedTransform transform; 01481 lookupTransform(target_frame, target_time, 01482 stamped_in.frame_id_,stamped_in.stamp_, 01483 fixed_frame, transform); 01484 01486 btVector3 end = stamped_in; 01487 btVector3 origin = btVector3(0,0,0); 01488 btVector3 output = (transform * end) - (transform * origin); 01489 stamped_out.setData( output); 01490 01491 stamped_out.stamp_ = transform.stamp_; 01492 stamped_out.frame_id_ = target_frame; 01493 }; 01494 01495 01496 void Transformer::transformPoint(const std::string& target_frame, const ros::Time& target_time, 01497 const Stamped<Point>& stamped_in, 01498 const std::string& fixed_frame, 01499 Stamped<Point>& stamped_out) const 01500 { 01501 StampedTransform transform; 01502 lookupTransform(target_frame, target_time, 01503 stamped_in.frame_id_,stamped_in.stamp_, 01504 fixed_frame, transform); 01505 01506 stamped_out.setData(transform * stamped_in); 01507 stamped_out.stamp_ = transform.stamp_; 01508 stamped_out.frame_id_ = target_frame; 01509 }; 01510 01511 void Transformer::transformPose(const std::string& target_frame, const ros::Time& target_time, 01512 const Stamped<Pose>& stamped_in, 01513 const std::string& fixed_frame, 01514 Stamped<Pose>& stamped_out) const 01515 { 01516 StampedTransform transform; 01517 lookupTransform(target_frame, target_time, 01518 stamped_in.frame_id_,stamped_in.stamp_, 01519 fixed_frame, transform); 01520 01521 stamped_out.setData(transform * stamped_in); 01522 stamped_out.stamp_ = transform.stamp_; 01523 stamped_out.frame_id_ = target_frame; 01524 }; 01525 01526 boost::signals::connection Transformer::addTransformsChangedListener(boost::function<void(void)> callback) 01527 { 01528 boost::mutex::scoped_lock lock(transforms_changed_mutex_); 01529 return transforms_changed_.connect(callback); 01530 } 01531 01532 void Transformer::removeTransformsChangedListener(boost::signals::connection c) 01533 { 01534 boost::mutex::scoped_lock lock(transforms_changed_mutex_); 01535 c.disconnect(); 01536 }