00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
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 Buffer::Buffer(ros::Duration cache_time, bool debug) :
00042 BufferCore(cache_time)
00043 {
00044 if(debug && !ros::service::exists("~tf2_frames", false))
00045 {
00046 ros::NodeHandle n("~");
00047 frames_server_ = n.advertiseService("tf2_frames", &Buffer::getFrames, this);
00048 }
00049 }
00050
00051 geometry_msgs::TransformStamped
00052 Buffer::lookupTransform(const std::string& target_frame, const std::string& source_frame,
00053 const ros::Time& time, const ros::Duration timeout) const
00054 {
00055 canTransform(target_frame, source_frame, time, timeout);
00056 return lookupTransform(target_frame, source_frame, time);
00057 }
00058
00059
00060 geometry_msgs::TransformStamped
00061 Buffer::lookupTransform(const std::string& target_frame, const ros::Time& target_time,
00062 const std::string& source_frame, const ros::Time& source_time,
00063 const std::string& fixed_frame, const ros::Duration timeout) const
00064 {
00065 canTransform(target_frame, target_time, source_frame, source_time, fixed_frame, timeout);
00066 return lookupTransform(target_frame, target_time, source_frame, source_time, fixed_frame);
00067 }
00068
00073 ros::Time now_fallback_to_wall()
00074 {
00075 try
00076 {
00077 return ros::Time::now();
00078 }
00079 catch (ros::TimeNotInitializedException ex)
00080 {
00081 ros::WallTime wt = ros::WallTime::now();
00082 return ros::Time(wt.sec, wt.nsec);
00083 }
00084 }
00085
00091 void sleep_fallback_to_wall(const ros::Duration& d)
00092 {
00093 try
00094 {
00095 d.sleep();
00096 }
00097 catch (ros::TimeNotInitializedException ex)
00098 {
00099 ros::WallDuration wd = ros::WallDuration(d.sec, d.nsec);
00100 wd.sleep();
00101 }
00102 }
00103
00104 void conditionally_append_timeout_info(std::string * errstr, const ros::Time& start_time,
00105 const ros::Duration& timeout)
00106 {
00107 if (errstr)
00108 {
00109 std::stringstream ss;
00110 ss << ". canTransform returned after "<< (now_fallback_to_wall() - start_time).toSec() \
00111 <<" timeout was " << timeout.toSec() << ".";
00112 (*errstr) += ss.str();
00113 }
00114 }
00115
00116 bool
00117 Buffer::canTransform(const std::string& target_frame, const std::string& source_frame,
00118 const ros::Time& time, const ros::Duration timeout, std::string* errstr) const
00119 {
00120
00121 if (errstr)
00122 {
00123 errstr->clear();
00124 }
00125
00126 if (!checkAndErrorDedicatedThreadPresent(errstr))
00127 return false;
00128
00129
00130 ros::Time start_time = now_fallback_to_wall();
00131 while (now_fallback_to_wall() < start_time + timeout &&
00132 !canTransform(target_frame, source_frame, time) &&
00133 (now_fallback_to_wall()+ros::Duration(3.0) >= start_time) &&
00134 (ros::ok() || !ros::isInitialized()))
00135 {
00136 sleep_fallback_to_wall(ros::Duration(0.01));
00137 }
00138 bool retval = canTransform(target_frame, source_frame, time, errstr);
00139 conditionally_append_timeout_info(errstr, start_time, timeout);
00140 return retval;
00141 }
00142
00143
00144 bool
00145 Buffer::canTransform(const std::string& target_frame, const ros::Time& target_time,
00146 const std::string& source_frame, const ros::Time& source_time,
00147 const std::string& fixed_frame, const ros::Duration timeout, std::string* errstr) const
00148 {
00149
00150 if (errstr)
00151 {
00152 errstr->clear();
00153 }
00154
00155 if (!checkAndErrorDedicatedThreadPresent(errstr))
00156 return false;
00157
00158
00159 ros::Time start_time = now_fallback_to_wall();
00160 while (now_fallback_to_wall() < start_time + timeout &&
00161 !canTransform(target_frame, target_time, source_frame, source_time, fixed_frame) &&
00162 (now_fallback_to_wall()+ros::Duration(3.0) >= start_time) &&
00163 (ros::ok() || !ros::isInitialized()))
00164 {
00165 sleep_fallback_to_wall(ros::Duration(0.01));
00166 }
00167 bool retval = canTransform(target_frame, target_time, source_frame, source_time, fixed_frame, errstr);
00168 conditionally_append_timeout_info(errstr, start_time, timeout);
00169 return retval;
00170 }
00171
00172
00173 bool Buffer::getFrames(tf2_msgs::FrameGraph::Request& req, tf2_msgs::FrameGraph::Response& res)
00174 {
00175 res.frame_yaml = allFramesAsYAML();
00176 return true;
00177 }
00178
00179
00180
00181 bool Buffer::checkAndErrorDedicatedThreadPresent(std::string* error_str) const
00182 {
00183 if (isUsingDedicatedThread())
00184 return true;
00185
00186
00187
00188 if (error_str)
00189 *error_str = tf2_ros::threading_error;
00190
00191 ROS_ERROR("%s", tf2_ros::threading_error.c_str());
00192 return false;
00193 }
00194
00195
00196
00197 }