.. _program_listing_file_include_tf2_buffer_core.h: Program Listing for File buffer_core.h ====================================== |exhale_lsh| :ref:`Return to documentation for file ` (``include/tf2/buffer_core.h``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp // Copyright 2008, Willow Garage, Inc. All rights reserved. // // Redistribution and use in source and binary forms, with or without // modification, are permitted provided that the following conditions are met: // // * Redistributions of source code must retain the above copyright // notice, this list of conditions and the following disclaimer. // // * Redistributions in binary form must reproduce the above copyright // notice, this list of conditions and the following disclaimer in the // documentation and/or other materials provided with the distribution. // // * Neither the name of the {copyright_holder} nor the names of its // contributors may be used to endorse or promote products derived from // this software without specific prior written permission. // // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE // POSSIBILITY OF SUCH DAMAGE. #ifndef TF2__BUFFER_CORE_H_ #define TF2__BUFFER_CORE_H_ #include #include #include #include #include #include #include #include #include #include #include #include "LinearMath/Transform.h" #include "geometry_msgs/msg/transform_stamped.hpp" #include "geometry_msgs/msg/velocity_stamped.hpp" #include "rcutils/logging_macros.h" #include "tf2/buffer_core_interface.h" #include "tf2/exceptions.h" #include "tf2/transform_storage.h" #include "tf2/visibility_control.h" namespace tf2 { typedef std::pair P_TimeAndFrameID; typedef uint64_t TransformableRequestHandle; class TimeCacheInterface; using TimeCacheInterfacePtr = std::shared_ptr; enum TransformableResult { TransformAvailable, TransformFailure, }; static constexpr Duration BUFFER_CORE_DEFAULT_CACHE_TIME = std::chrono::seconds(10); class BufferCore : public BufferCoreInterface { public: /************* Constants ***********************/ TF2_PUBLIC static const uint32_t MAX_GRAPH_DEPTH = 1000UL; TF2_PUBLIC explicit BufferCore(tf2::Duration cache_time = BUFFER_CORE_DEFAULT_CACHE_TIME); TF2_PUBLIC virtual ~BufferCore(void); TF2_PUBLIC void clear() override; TF2_PUBLIC bool setTransform( const geometry_msgs::msg::TransformStamped & transform, const std::string & authority, bool is_static = false); /*********** Accessors *************/ TF2_PUBLIC geometry_msgs::msg::TransformStamped lookupTransform( const std::string & target_frame, const std::string & source_frame, const TimePoint & time) const override; TF2_PUBLIC geometry_msgs::msg::TransformStamped lookupTransform( const std::string & target_frame, const TimePoint & target_time, const std::string & source_frame, const TimePoint & source_time, const std::string & fixed_frame) const override; TF2_PUBLIC geometry_msgs::msg::VelocityStamped lookupVelocity( const std::string & tracking_frame, const std::string & observation_frame, const TimePoint & time, const tf2::Duration & averaging_interval) const; TF2_PUBLIC geometry_msgs::msg::VelocityStamped lookupVelocity( const std::string & tracking_frame, const std::string & observation_frame, const std::string & reference_frame, const tf2::Vector3 & reference_point, const std::string & reference_point_frame, const TimePoint & time, const tf2::Duration & duration) const; TF2_PUBLIC bool canTransform( const std::string & target_frame, const std::string & source_frame, const TimePoint & time, std::string * error_msg = nullptr) const override; TF2_PUBLIC bool canTransform( const std::string & target_frame, const TimePoint & target_time, const std::string & source_frame, const TimePoint & source_time, const std::string & fixed_frame, std::string * error_msg = nullptr) const override; TF2_PUBLIC std::vector getAllFrameNames() const override; TF2_PUBLIC std::string allFramesAsYAML(TimePoint current_time) const; TF2_PUBLIC std::string allFramesAsYAML() const; TF2_PUBLIC std::string allFramesAsString() const; using TransformableCallback = std::function< void (TransformableRequestHandle request_handle, const std::string & target_frame, const std::string & source_frame, TimePoint time, TransformableResult result)>; TF2_PUBLIC TransformableRequestHandle addTransformableRequest( const TransformableCallback & cb, const std::string & target_frame, const std::string & source_frame, TimePoint time); TF2_PUBLIC void cancelTransformableRequest(TransformableRequestHandle handle); // Tell the buffer that there are multiple threads servicing it. // This is useful for derived classes to know if they can block or not. TF2_PUBLIC void setUsingDedicatedThread(bool value) {using_dedicated_thread_ = value;} // Get the state of using_dedicated_thread_ TF2_PUBLIC bool isUsingDedicatedThread() const {return using_dedicated_thread_;} /* Backwards compatability section for tf::Transformer you should not use these */ TF2_PUBLIC bool _frameExists(const std::string & frame_id_str) const; TF2_PUBLIC bool _getParent(const std::string & frame_id, TimePoint time, std::string & parent) const; TF2_PUBLIC void _getFrameStrings(std::vector & ids) const; TF2_PUBLIC CompactFrameID _lookupFrameNumber(const std::string & frameid_str) const { return lookupFrameNumber(frameid_str); } TF2_PUBLIC CompactFrameID _lookupOrInsertFrameNumber(const std::string & frameid_str) { return lookupOrInsertFrameNumber(frameid_str); } TF2_PUBLIC tf2::TF2Error _getLatestCommonTime( CompactFrameID target_frame, CompactFrameID source_frame, TimePoint & time, std::string * error_string) const { std::unique_lock lock(frame_mutex_); return getLatestCommonTime(target_frame, source_frame, time, error_string); } TF2_PUBLIC CompactFrameID _validateFrameId( const char * function_name_arg, const std::string & frame_id) const { return validateFrameId(function_name_arg, frame_id); } TF2_PUBLIC tf2::Duration getCacheLength() {return cache_time_;} TF2_PUBLIC std::string _allFramesAsDot(TimePoint current_time) const; TF2_PUBLIC std::string _allFramesAsDot() const; TF2_PUBLIC void _chainAsVector( const std::string & target_frame, TimePoint target_time, const std::string & source_frame, TimePoint source_time, const std::string & fixed_frame, std::vector & output) const; private: /******************** Internal Storage ****************/ typedef std::vector V_TimeCacheInterface; V_TimeCacheInterface frames_; mutable std::mutex frame_mutex_; typedef std::unordered_map M_StringToCompactFrameID; M_StringToCompactFrameID frameIDs_; std::vector frameIDs_reverse_; std::map frame_authority_; tf2::Duration cache_time_; typedef uint32_t TransformableCallbackHandle; typedef std::unordered_map M_TransformableCallback; M_TransformableCallback transformable_callbacks_; uint32_t transformable_callbacks_counter_; std::mutex transformable_callbacks_mutex_; struct TransformableRequest { TimePoint time; TransformableRequestHandle request_handle; TransformableCallbackHandle cb_handle; CompactFrameID target_id; CompactFrameID source_id; std::string target_string; std::string source_string; }; typedef std::vector V_TransformableRequest; V_TransformableRequest transformable_requests_; std::mutex transformable_requests_mutex_; uint64_t transformable_requests_counter_; bool using_dedicated_thread_; /************************* Internal Functions ****************************/ std::string allFramesAsStringNoLock() const; bool setTransformImpl( const tf2::Transform & transform_in, const std::string frame_id, const std::string child_frame_id, const TimePoint stamp, const std::string & authority, bool is_static); void lookupTransformImpl( const std::string & target_frame, const std::string & source_frame, const TimePoint & time_in, tf2::Transform & transform, TimePoint & time_out) const; void lookupTransformImpl( const std::string & target_frame, const TimePoint & target_time, const std::string & source_frame, const TimePoint & source_time, const std::string & fixed_frame, tf2::Transform & transform, TimePoint & time_out) const; TimeCacheInterfacePtr getFrame(CompactFrameID c_frame_id) const; TimeCacheInterfacePtr allocateFrame(CompactFrameID cfid, bool is_static); CompactFrameID validateFrameId( const char * function_name_arg, const std::string & frame_id, std::string * error_msg) const; CompactFrameID validateFrameId( const char * function_name_arg, const std::string & frame_id) const; CompactFrameID lookupFrameNumber(const std::string & frameid_str) const; CompactFrameID lookupOrInsertFrameNumber(const std::string & frameid_str); const std::string & lookupFrameString(CompactFrameID frame_id_num) const; void createConnectivityErrorString( CompactFrameID source_frame, CompactFrameID target_frame, std::string * out) const; tf2::TF2Error getLatestCommonTime( CompactFrameID target_frame, CompactFrameID source_frame, TimePoint & time, std::string * error_string) const; template tf2::TF2Error walkToTopParent( F & f, TimePoint time, CompactFrameID target_id, CompactFrameID source_id, std::string * error_string, std::vector * frame_chain) const; void testTransformableRequests(); // Actual implementation to walk the transform tree and find out if a transform exists. bool canTransformInternal( CompactFrameID target_id, CompactFrameID source_id, const TimePoint & time, std::string * error_msg) const; }; } // namespace tf2 #endif // TF2__BUFFER_CORE_H_