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 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   // poll for transform if timeout is set
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   // poll for transform if timeout is set
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 }


tf2_ros
Author(s): Eitan Marder-Eppstein, Wim Meeussen
autogenerated on Mon Oct 6 2014 00:12:48