buffer.cpp
Go to the documentation of this file.
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 
00033 #include "tf2_ros/buffer.h"
00034 
00035 #include <ros/assert.h>
00036 #include <sstream>
00037 
00038 namespace tf2_ros
00039 {
00040 
00041 static const double CAN_TRANSFORM_POLLING_SCALE = 0.01;
00042 
00043 Buffer::Buffer(ros::Duration cache_time, bool debug) :
00044   BufferCore(cache_time)
00045 {
00046   if(debug && !ros::service::exists("~tf2_frames", false))
00047   {
00048     ros::NodeHandle n("~");
00049     frames_server_ = n.advertiseService("tf2_frames", &Buffer::getFrames, this);
00050   }
00051 }
00052 
00053 geometry_msgs::TransformStamped 
00054 Buffer::lookupTransform(const std::string& target_frame, const std::string& source_frame,
00055                         const ros::Time& time, const ros::Duration timeout) const
00056 {
00057   canTransform(target_frame, source_frame, time, timeout);
00058   return lookupTransform(target_frame, source_frame, time);
00059 }
00060 
00061 
00062 geometry_msgs::TransformStamped 
00063 Buffer::lookupTransform(const std::string& target_frame, const ros::Time& target_time,
00064                         const std::string& source_frame, const ros::Time& source_time,
00065                         const std::string& fixed_frame, const ros::Duration timeout) const
00066 {
00067   canTransform(target_frame, target_time, source_frame, source_time, fixed_frame, timeout);
00068   return lookupTransform(target_frame, target_time, source_frame, source_time, fixed_frame);
00069 }
00070 
00075 ros::Time now_fallback_to_wall()
00076 {
00077   try
00078   {
00079     return ros::Time::now();
00080   }
00081   catch (ros::TimeNotInitializedException ex)
00082   {
00083     ros::WallTime wt = ros::WallTime::now(); 
00084     return ros::Time(wt.sec, wt.nsec); 
00085   }
00086 }
00087 
00093 void sleep_fallback_to_wall(const ros::Duration& d)
00094 {
00095   try
00096   {
00097       d.sleep();
00098   }
00099   catch (ros::TimeNotInitializedException ex)
00100   {
00101     ros::WallDuration wd = ros::WallDuration(d.sec, d.nsec); 
00102     wd.sleep();
00103   }
00104 }
00105 
00106 void conditionally_append_timeout_info(std::string * errstr, const ros::Time& start_time,
00107                                        const ros::Duration& timeout)
00108 {
00109   if (errstr)
00110   {
00111     std::stringstream ss;
00112     ss << ". canTransform returned after "<< (now_fallback_to_wall() - start_time).toSec() \
00113        <<" timeout was " << timeout.toSec() << ".";
00114     (*errstr) += ss.str();
00115   }
00116 }
00117 
00118 bool
00119 Buffer::canTransform(const std::string& target_frame, const std::string& source_frame, 
00120                      const ros::Time& time, const ros::Duration timeout, std::string* errstr) const
00121 {
00122   // Clear the errstr before populating it if it's valid.
00123   if (errstr)
00124     {
00125       errstr->clear();
00126     }
00127 
00128   if (!checkAndErrorDedicatedThreadPresent(errstr))
00129     return false;
00130 
00131   // poll for transform if timeout is set
00132   ros::Time start_time = now_fallback_to_wall();
00133   const ros::Duration sleep_duration = timeout * CAN_TRANSFORM_POLLING_SCALE;
00134   while (now_fallback_to_wall() < start_time + timeout && 
00135          !canTransform(target_frame, source_frame, time) &&
00136          (now_fallback_to_wall()+ros::Duration(3.0) >= start_time) &&  //don't wait when we detect a bag loop
00137          (ros::ok() || !ros::isInitialized())) // Make sure we haven't been stopped (won't work for pytf)
00138     {
00139       sleep_fallback_to_wall(sleep_duration);
00140     }
00141   bool retval = canTransform(target_frame, source_frame, time, errstr);
00142   conditionally_append_timeout_info(errstr, start_time, timeout);
00143   return retval;
00144 }
00145 
00146     
00147 bool
00148 Buffer::canTransform(const std::string& target_frame, const ros::Time& target_time,
00149                      const std::string& source_frame, const ros::Time& source_time,
00150                      const std::string& fixed_frame, const ros::Duration timeout, std::string* errstr) const
00151 {
00152   // Clear the errstr before populating it if it's valid.
00153   if (errstr)
00154     {
00155       errstr->clear();
00156     }
00157 
00158   if (!checkAndErrorDedicatedThreadPresent(errstr))
00159     return false;
00160 
00161   // poll for transform if timeout is set
00162   ros::Time start_time = now_fallback_to_wall();
00163   const ros::Duration sleep_duration = timeout * CAN_TRANSFORM_POLLING_SCALE;
00164   while (now_fallback_to_wall() < start_time + timeout && 
00165          !canTransform(target_frame, target_time, source_frame, source_time, fixed_frame) &&
00166          (now_fallback_to_wall()+ros::Duration(3.0) >= start_time) &&  //don't wait when we detect a bag loop
00167          (ros::ok() || !ros::isInitialized())) // Make sure we haven't been stopped (won't work for pytf)
00168          {  
00169            sleep_fallback_to_wall(sleep_duration);
00170          }
00171   bool retval = canTransform(target_frame, target_time, source_frame, source_time, fixed_frame, errstr);
00172   conditionally_append_timeout_info(errstr, start_time, timeout);
00173   return retval; 
00174 }
00175 
00176 
00177 bool Buffer::getFrames(tf2_msgs::FrameGraph::Request& req, tf2_msgs::FrameGraph::Response& res) 
00178 {
00179   res.frame_yaml = allFramesAsYAML();
00180   return true;
00181 }
00182 
00183 
00184 
00185 bool Buffer::checkAndErrorDedicatedThreadPresent(std::string* error_str) const
00186 {
00187   if (isUsingDedicatedThread())
00188     return true;
00189   
00190 
00191 
00192   if (error_str)
00193     *error_str = tf2_ros::threading_error;
00194 
00195   ROS_ERROR("%s", tf2_ros::threading_error.c_str());
00196   return false;
00197 }
00198 
00199 
00200 
00201 }


tf2_ros
Author(s): Eitan Marder-Eppstein, Wim Meeussen
autogenerated on Thu Jun 6 2019 20:23:00