buffer_core.h
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 
00032 #ifndef TF2_BUFFER_CORE_H
00033 #define TF2_BUFFER_CORE_H
00034 
00035 #include "transform_storage.h"
00036 
00037 #include <boost/signals.hpp>
00038 
00039 #include <string>
00040 
00041 #include "ros/duration.h"
00042 #include "ros/time.h"
00043 //#include "geometry_msgs/TwistStamped.h"
00044 #include "geometry_msgs/TransformStamped.h"
00045 
00047 //#include "tf/tf.h"
00048 
00049 #include <boost/unordered_map.hpp>
00050 #include <boost/thread/mutex.hpp>
00051 #include <boost/function.hpp>
00052 #include <boost/shared_ptr.hpp>
00053 
00054 namespace tf2
00055 {
00056 
00057 typedef std::pair<ros::Time, CompactFrameID> P_TimeAndFrameID;
00058 typedef uint32_t TransformableCallbackHandle;
00059 typedef uint64_t TransformableRequestHandle;
00060 
00061 class TimeCacheInterface;
00062 typedef boost::shared_ptr<TimeCacheInterface> TimeCacheInterfacePtr;
00063 
00064 enum TransformableResult
00065 {
00066   TransformAvailable,
00067   TransformFailure,
00068 };
00069 
00088 class BufferCore
00089 {
00090 public:
00091   /************* Constants ***********************/
00092   static const int DEFAULT_CACHE_TIME = 10;  
00093   static const uint32_t MAX_GRAPH_DEPTH = 1000UL;  
00094 
00100   BufferCore(ros::Duration cache_time_ = ros::Duration(DEFAULT_CACHE_TIME));
00101   virtual ~BufferCore(void);
00102 
00104   void clear();
00105 
00112   bool setTransform(const geometry_msgs::TransformStamped& transform, const std::string & authority, bool is_static = false);
00113 
00114   /*********** Accessors *************/
00115 
00125   geometry_msgs::TransformStamped 
00126     lookupTransform(const std::string& target_frame, const std::string& source_frame,
00127                     const ros::Time& time) const;
00128 
00141   geometry_msgs::TransformStamped
00142     lookupTransform(const std::string& target_frame, const ros::Time& target_time,
00143                     const std::string& source_frame, const ros::Time& source_time,
00144                     const std::string& fixed_frame) const;
00145   
00166   /*
00167   geometry_msgs::Twist
00168     lookupTwist(const std::string& tracking_frame, const std::string& observation_frame, const std::string& reference_frame,
00169                 const tf::Point & reference_point, const std::string& reference_point_frame, 
00170                 const ros::Time& time, const ros::Duration& averaging_interval) const;
00171   */
00184   /*
00185   geometry_msgs::Twist
00186     lookupTwist(const std::string& tracking_frame, const std::string& observation_frame, 
00187                 const ros::Time& time, const ros::Duration& averaging_interval) const;
00188   */
00196   bool canTransform(const std::string& target_frame, const std::string& source_frame,
00197                     const ros::Time& time, std::string* error_msg = NULL) const;
00198   
00208   bool canTransform(const std::string& target_frame, const ros::Time& target_time,
00209                     const std::string& source_frame, const ros::Time& source_time,
00210                     const std::string& fixed_frame, std::string* error_msg = NULL) const;
00211 
00215   std::string allFramesAsYAML() const;
00216 
00220   std::string allFramesAsString() const;
00221   
00222   typedef boost::function<void(TransformableRequestHandle request_handle, const std::string& target_frame, const std::string& source_frame,
00223                                ros::Time time, TransformableResult result)> TransformableCallback;
00224 
00226   TransformableCallbackHandle addTransformableCallback(const TransformableCallback& cb);
00228   void removeTransformableCallback(TransformableCallbackHandle handle);
00230   TransformableRequestHandle addTransformableRequest(TransformableCallbackHandle handle, const std::string& target_frame, const std::string& source_frame, ros::Time time);
00232   void cancelTransformableRequest(TransformableRequestHandle handle);
00233 
00234 
00235 
00236 
00237   // Tell the buffer that there are multiple threads serviciing it. 
00238   // This is useful for derived classes to know if they can block or not. 
00239   void setUsingDedicatedThread(bool value) { using_dedicated_thread_ = value;};
00240   // Get the state of using_dedicated_thread_
00241   bool isUsingDedicatedThread() const { return using_dedicated_thread_;};
00242   
00243 
00244 
00245 
00246   /* Backwards compatability section for tf::Transformer you should not use these
00247    */
00248 
00256   boost::signals::connection _addTransformsChangedListener(boost::function<void(void)> callback);
00257   void _removeTransformsChangedListener(boost::signals::connection c);
00258 
00259 
00262   bool _frameExists(const std::string& frame_id_str) const;
00263 
00268   bool _getParent(const std::string& frame_id, ros::Time time, std::string& parent) const;
00269 
00271   void _getFrameStrings(std::vector<std::string>& ids) const;
00272 
00273 
00274   CompactFrameID _lookupFrameNumber(const std::string& frameid_str) const { 
00275     return lookupFrameNumber(frameid_str); 
00276   }
00277   CompactFrameID _lookupOrInsertFrameNumber(const std::string& frameid_str) {
00278     return lookupOrInsertFrameNumber(frameid_str); 
00279   }
00280 
00281   int _getLatestCommonTime(CompactFrameID target_frame, CompactFrameID source_frame, ros::Time& time, std::string* error_string) const {
00282     boost::mutex::scoped_lock lock(frame_mutex_);
00283     return getLatestCommonTime(target_frame, source_frame, time, error_string);
00284   }
00285 
00286   CompactFrameID _validateFrameId(const char* function_name_arg, const std::string& frame_id) const {
00287     return validateFrameId(function_name_arg, frame_id);
00288   }
00289 
00291   ros::Duration getCacheLength() { return cache_time_;}
00292 
00296   std::string _allFramesAsDot() const;
00297 
00301   void _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;
00302 
00303 private:
00304 
00308   std::string allFramesAsStringNoLock() const;  
00309 
00310 
00311   /******************** Internal Storage ****************/
00312   
00315   typedef std::vector<TimeCacheInterfacePtr> V_TimeCacheInterface;
00316   V_TimeCacheInterface frames_;
00317   
00319   mutable boost::mutex frame_mutex_;
00320 
00322   typedef boost::unordered_map<std::string, CompactFrameID> M_StringToCompactFrameID;
00323   M_StringToCompactFrameID frameIDs_;
00325   std::vector<std::string> frameIDs_reverse;
00327   std::map<CompactFrameID, std::string> frame_authority_;
00328 
00329 
00331   ros::Duration cache_time_;
00332 
00333   mutable std::vector<P_TimeAndFrameID> lct_cache_;
00334 
00335   typedef boost::unordered_map<TransformableCallbackHandle, TransformableCallback> M_TransformableCallback;
00336   M_TransformableCallback transformable_callbacks_;
00337   uint32_t transformable_callbacks_counter_;
00338   boost::mutex transformable_callbacks_mutex_;
00339 
00340   struct TransformableRequest
00341   {
00342     ros::Time time;
00343     TransformableRequestHandle request_handle;
00344     TransformableCallbackHandle cb_handle;
00345     CompactFrameID target_id;
00346     CompactFrameID source_id;
00347     std::string target_string;
00348     std::string source_string;
00349   };
00350   typedef std::vector<TransformableRequest> V_TransformableRequest;
00351   V_TransformableRequest transformable_requests_;
00352   boost::mutex transformable_requests_mutex_;
00353   uint64_t transformable_requests_counter_;
00354 
00355   struct RemoveRequestByCallback;
00356   struct RemoveRequestByID;
00357 
00358   // Backwards compatability for tf message_filter
00359   typedef boost::signal<void(void)> TransformsChangedSignal;
00361   TransformsChangedSignal _transforms_changed_;
00362 
00363 
00364   /************************* Internal Functions ****************************/
00365 
00372   TimeCacheInterfacePtr getFrame(CompactFrameID c_frame_id) const;
00373 
00374   TimeCacheInterfacePtr allocateFrame(CompactFrameID cfid, bool is_static);
00375 
00376 
00377   bool warnFrameId(const char* function_name_arg, const std::string& frame_id) const;
00378   CompactFrameID validateFrameId(const char* function_name_arg, const std::string& frame_id) const;
00379 
00381   CompactFrameID lookupFrameNumber(const std::string& frameid_str) const;
00382 
00384   CompactFrameID lookupOrInsertFrameNumber(const std::string& frameid_str);
00385 
00387   const std::string& lookupFrameString(CompactFrameID frame_id_num) const;
00388 
00389   void createConnectivityErrorString(CompactFrameID source_frame, CompactFrameID target_frame, std::string* out) const;
00390 
00393   int getLatestCommonTime(CompactFrameID target_frame, CompactFrameID source_frame, ros::Time& time, std::string* error_string) const;
00394 
00395   template<typename F>
00396   int walkToTopParent(F& f, ros::Time time, CompactFrameID target_id, CompactFrameID source_id, std::string* error_string) const;
00397 
00398   void testTransformableRequests();
00399   bool canTransformInternal(CompactFrameID target_id, CompactFrameID source_id,
00400                     const ros::Time& time, std::string* error_msg) const;
00401   bool canTransformNoLock(CompactFrameID target_id, CompactFrameID source_id,
00402                       const ros::Time& time, std::string* error_msg) const;
00403 
00404 
00405   //Whether it is safe to use canTransform with a timeout. (If another thread is not provided it will always timeout.)
00406   bool using_dedicated_thread_;
00407   
00408 
00409 };
00410 
00411 
00412 
00413 
00414 };
00415 
00416 #endif //TF2_CORE_H


tf2
Author(s): Tully Foote, Eitan Marder-Eppstein, Wim Meeussen
autogenerated on Thu Aug 27 2015 13:09:58