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 namespace tf2
00036 {
00037
00038 Buffer::Buffer(ros::Duration cache_time, bool debug) : BufferCore(cache_time)
00039 {
00040 if(debug && !ros::service::exists("~tf2_frames", false))
00041 {
00042 ros::NodeHandle n("~");
00043 frames_server_ = n.advertiseService("tf2_frames", &Buffer::getFrames, this);
00044 }
00045 }
00046
00047 geometry_msgs::TransformStamped
00048 Buffer::lookupTransform(const std::string& target_frame, const std::string& source_frame,
00049 const ros::Time& time, const ros::Duration timeout) const
00050 {
00051 canTransform(target_frame, source_frame, time, timeout);
00052 return lookupTransform(target_frame, source_frame, time);
00053 }
00054
00055
00056 geometry_msgs::TransformStamped
00057 Buffer::lookupTransform(const std::string& target_frame, const ros::Time& target_time,
00058 const std::string& source_frame, const ros::Time& source_time,
00059 const std::string& fixed_frame, const ros::Duration timeout) const
00060 {
00061 canTransform(target_frame, target_time, source_frame, source_time, fixed_frame, timeout);
00062 return lookupTransform(target_frame, target_time, source_frame, source_time, fixed_frame);
00063 }
00064
00065
00066 bool
00067 Buffer::canTransform(const std::string& target_frame, const std::string& source_frame,
00068 const ros::Time& time, const ros::Duration timeout, std::string* errstr) const
00069 {
00070
00071 ros::Time start_time = ros::Time::now();
00072 while (ros::Time::now() < start_time + timeout &&
00073 !canTransform(target_frame, source_frame, time))
00074 ros::Duration(0.01).sleep();
00075 return canTransform(target_frame, source_frame, time, errstr);
00076 }
00077
00078
00079 bool
00080 Buffer::canTransform(const std::string& target_frame, const ros::Time& target_time,
00081 const std::string& source_frame, const ros::Time& source_time,
00082 const std::string& fixed_frame, const ros::Duration timeout, std::string* errstr) const
00083 {
00084
00085 ros::Time start_time = ros::Time::now();
00086 while (ros::Time::now() < start_time + timeout &&
00087 !canTransform(target_frame, target_time, source_frame, source_time, fixed_frame))
00088 ros::Duration(0.01).sleep();
00089 return canTransform(target_frame, target_time, source_frame, source_time, fixed_frame, errstr);
00090 }
00091
00092
00093
00094
00095 }