buffer_core.h
Go to the documentation of this file.
1 #include "sick_scan/sick_scan_base.h" /* Base definitions included in all header files, added by add_sick_scan_base_header.py. Do not edit this line. */
2 /*
3  * Copyright (c) 2008, Willow Garage, Inc.
4  * All rights reserved.
5  *
6  * Redistribution and use in source and binary forms, with or without
7  * modification, are permitted provided that the following conditions are met:
8  *
9  * * Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * * Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in the
13  * documentation and/or other materials provided with the distribution.
14  * * Neither the name of the Willow Garage, Inc. nor the names of its
15  * contributors may be used to endorse or promote products derived from
16  * this software without specific prior written permission.
17  *
18  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
21  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
22  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
23  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
24  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
25  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
26  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
27  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
28  * POSSIBILITY OF SUCH DAMAGE.
29  */
30 
33 #ifndef TF2_BUFFER_CORE_H
34 #define TF2_BUFFER_CORE_H
35 
36 #include "transform_storage.h"
37 
38 //#include <boost/signals2.hpp>
39 
40 #include <string>
41 
42 #include "ros/duration.h"
43 #include "ros/time.h"
44 //#include "geometry_msgs/TwistStamped.h"
46 
48 //#include "tf/tf.h"
49 
50 //#include <boost/unordered_map.hpp>
51 #include <mutex>
52 //#include <boost/function.hpp>
53 #include <memory>
54 
55 namespace tf2
56 {
57 
58 typedef std::pair<ros::Time, CompactFrameID> P_TimeAndFrameID;
59 typedef uint32_t TransformableCallbackHandle;
60 typedef uint64_t TransformableRequestHandle;
61 
63 typedef std::shared_ptr<TimeCacheInterface> TimeCacheInterfacePtr;
64 
66 {
69 };
70 
89 class BufferCore
90 {
91 public:
92  /************* Constants ***********************/
93  static const int DEFAULT_CACHE_TIME = 10;
94  static const uint32_t MAX_GRAPH_DEPTH = 1000UL;
95 
102  virtual ~BufferCore(void);
103 
105  void clear();
106 
113  bool setTransform(const geometry_msgs::TransformStamped& transform, const std::string & authority, bool is_static = false);
114 
115  /*********** Accessors *************/
116 
127  lookupTransform(const std::string& target_frame, const std::string& source_frame,
128  const ros::Time& time) const;
129 
143  lookupTransform(const std::string& target_frame, const ros::Time& target_time,
144  const std::string& source_frame, const ros::Time& source_time,
145  const std::string& fixed_frame) const;
146 
147  /* \brief Lookup the twist of the tracking_frame with respect to the observation frame in the reference_frame using the reference point
148  * \param tracking_frame The frame to track
149  * \param observation_frame The frame from which to measure the twist
150  * \param reference_frame The reference frame in which to express the twist
151  * \param reference_point The reference point with which to express the twist
152  * \param reference_point_frame The frame_id in which the reference point is expressed
153  * \param time The time at which to get the velocity
154  * \param duration The period over which to average
155  * \return twist The twist output
156  *
157  * This will compute the average velocity on the interval
158  * (time - duration/2, time+duration/2). If that is too close to the most
159  * recent reading, in which case it will shift the interval up to
160  * duration/2 to prevent extrapolation.
161  *
162  * Possible exceptions tf2::LookupException, tf2::ConnectivityException,
163  * tf2::ExtrapolationException, tf2::InvalidArgumentException
164  *
165  * New in geometry 1.1
166  */
167  /*
168  geometry_msgs::Twist
169  lookupTwist(const std::string& tracking_frame, const std::string& observation_frame, const std::string& reference_frame,
170  const tf::Point & reference_point, const std::string& reference_point_frame,
171  const ros::Time& time, const ros::Duration& averaging_interval) const;
172  */
173  /* \brief lookup the twist of the tracking frame with respect to the observational frame
174  *
175  * This is a simplified version of
176  * lookupTwist with it assumed that the reference point is the
177  * origin of the tracking frame, and the reference frame is the
178  * observation frame.
179  *
180  * Possible exceptions tf2::LookupException, tf2::ConnectivityException,
181  * tf2::ExtrapolationException, tf2::InvalidArgumentException
182  *
183  * New in geometry 1.1
184  */
185  /*
186  geometry_msgs::Twist
187  lookupTwist(const std::string& tracking_frame, const std::string& observation_frame,
188  const ros::Time& time, const ros::Duration& averaging_interval) const;
189  */
197  bool canTransform(const std::string& target_frame, const std::string& source_frame,
198  const ros::Time& time, std::string* error_msg = NULL) const;
199 
209  bool canTransform(const std::string& target_frame, const ros::Time& target_time,
210  const std::string& source_frame, const ros::Time& source_time,
211  const std::string& fixed_frame, std::string* error_msg = NULL) const;
212 
216  std::string allFramesAsYAML(double current_time) const;
217 
220  std::string allFramesAsYAML() const;
221 
225  std::string allFramesAsString() const;
226 
227  typedef std::function<void(TransformableRequestHandle request_handle, const std::string& target_frame, const std::string& source_frame,
229 
235  TransformableRequestHandle addTransformableRequest(TransformableCallbackHandle handle, const std::string& target_frame, const std::string& source_frame, ros::Time time);
238 
239 
240 
241 
242  // Tell the buffer that there are multiple threads serviciing it.
243  // This is useful for derived classes to know if they can block or not.
244  void setUsingDedicatedThread(bool value) { using_dedicated_thread_ = value;};
245  // Get the state of using_dedicated_thread_
246  bool isUsingDedicatedThread() const { return using_dedicated_thread_;};
247 
248 
249 
250 
251  /* Backwards compatability section for tf::Transformer you should not use these
252  */
253 
261  boost::signals2::connection _addTransformsChangedListener(std::function<void(void)> callback);
262  void _removeTransformsChangedListener(boost::signals2::connection c);
263 
264 
267  bool _frameExists(const std::string& frame_id_str) const;
268 
273  bool _getParent(const std::string& frame_id, ros::Time time, std::string& parent) const;
274 
276  void _getFrameStrings(std::vector<std::string>& ids) const;
277 
278 
279  CompactFrameID _lookupFrameNumber(const std::string& frameid_str) const {
280  return lookupFrameNumber(frameid_str);
281  }
282  CompactFrameID _lookupOrInsertFrameNumber(const std::string& frameid_str) {
283  return lookupOrInsertFrameNumber(frameid_str);
284  }
285 
286  int _getLatestCommonTime(CompactFrameID target_frame, CompactFrameID source_frame, ros::Time& time, std::string* error_string) const {
287  std::lock_guard<std::mutex> lock(frame_mutex_);
288  return getLatestCommonTime(target_frame, source_frame, time, error_string);
289  }
290 
291  CompactFrameID _validateFrameId(const char* function_name_arg, const std::string& frame_id) const {
292  return validateFrameId(function_name_arg, frame_id);
293  }
294 
297 
301  std::string _allFramesAsDot(double current_time) const;
302  std::string _allFramesAsDot() const;
303 
307  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;
308 
309 private:
310 
314  std::string allFramesAsStringNoLock() const;
315 
316 
317  /******************** Internal Storage ****************/
318 
321  typedef std::vector<TimeCacheInterfacePtr> V_TimeCacheInterface;
323 
325  mutable std::mutex frame_mutex_;
326 
328  typedef boost::unordered_map<std::string, CompactFrameID> M_StringToCompactFrameID;
331  std::vector<std::string> frameIDs_reverse;
333  std::map<CompactFrameID, std::string> frame_authority_;
334 
335 
338 
339  typedef boost::unordered_map<TransformableCallbackHandle, TransformableCallback> M_TransformableCallback;
343 
344  struct TransformableRequest
345  {
346  ros::Time time;
351  std::string target_string;
352  std::string source_string;
353  };
354  typedef std::vector<TransformableRequest> V_TransformableRequest;
358 
359  struct RemoveRequestByCallback;
360  struct RemoveRequestByID;
361 
362  // Backwards compatability for tf message_filter
363  typedef boost::signals2::signal<void(void)> TransformsChangedSignal;
366 
367 
368  /************************* Internal Functions ****************************/
369 
377 
378  TimeCacheInterfacePtr allocateFrame(CompactFrameID cfid, bool is_static);
379 
380 
381  bool warnFrameId(const char* function_name_arg, const std::string& frame_id) const;
382  CompactFrameID validateFrameId(const char* function_name_arg, const std::string& frame_id) const;
383 
385  CompactFrameID lookupFrameNumber(const std::string& frameid_str) const;
386 
388  CompactFrameID lookupOrInsertFrameNumber(const std::string& frameid_str);
389 
391  const std::string& lookupFrameString(CompactFrameID frame_id_num) const;
392 
393  void createConnectivityErrorString(CompactFrameID source_frame, CompactFrameID target_frame, std::string* out) const;
394 
397  int getLatestCommonTime(CompactFrameID target_frame, CompactFrameID source_frame, ros::Time& time, std::string* error_string) const;
398 
399  template<typename F>
400  int walkToTopParent(F& f, ros::Time time, CompactFrameID target_id, CompactFrameID source_id, std::string* error_string) const;
401 
404  template<typename F>
405  int walkToTopParent(F& f, ros::Time time, CompactFrameID target_id, CompactFrameID source_id, std::string* error_string, std::vector<CompactFrameID> *frame_chain) const;
406 
408  bool canTransformInternal(CompactFrameID target_id, CompactFrameID source_id,
409  const ros::Time& time, std::string* error_msg) const;
410  bool canTransformNoLock(CompactFrameID target_id, CompactFrameID source_id,
411  const ros::Time& time, std::string* error_msg) const;
412 
413 
414  //Whether it is safe to use canTransform with a timeout. (If another thread is not provided it will always timeout.)
416 
417 public:
418  friend class TestBufferCore; // For unit testing
419 
420 };
421 
423 class TestBufferCore
424 {
425 public:
426  int _walkToTopParent(BufferCore& buffer, ros::Time time, CompactFrameID target_id, CompactFrameID source_id, std::string* error_string, std::vector<CompactFrameID> *frame_chain) const;
427  const std::string& _lookupFrameString(BufferCore& buffer, CompactFrameID frame_id_num) const
428  {
429  return buffer.lookupFrameString(frame_id_num);
430  }
431 };
432 }
433 
434 #endif //TF2_CORE_H
tf2::BufferCore::transformable_requests_counter_
uint64_t transformable_requests_counter_
Definition: buffer_core.h:357
tf2::BufferCore::getLatestCommonTime
int getLatestCommonTime(CompactFrameID target_frame, CompactFrameID source_frame, ros::Time &time, std::string *error_string) const
tf2::BufferCore::setUsingDedicatedThread
void setUsingDedicatedThread(bool value)
NULL
#define NULL
tf2::BufferCore::testTransformableRequests
void testTransformableRequests()
tf2::BufferCore::_transforms_changed_
TransformsChangedSignal _transforms_changed_
Signal which is fired whenever new transform data has arrived, from the thread the data arrived in.
Definition: buffer_core.h:365
tf2::BufferCore::warnFrameId
bool warnFrameId(const char *function_name_arg, const std::string &frame_id) const
boost::shared_ptr
Definition: message_forward.h:49
tf2::BufferCore::TransformableRequest::target_id
CompactFrameID target_id
Definition: buffer_core.h:349
tf2::BufferCore::TransformableCallback
boost::function< void(TransformableRequestHandle request_handle, const std::string &target_frame, const std::string &source_frame, ros::Time time, TransformableResult result)> TransformableCallback
tf2::TimeCacheInterfacePtr
boost::shared_ptr< TimeCacheInterface > TimeCacheInterfacePtr
Definition: time_cache.h:89
tf2::BufferCore::allocateFrame
TimeCacheInterfacePtr allocateFrame(CompactFrameID cfid, bool is_static)
tf2::BufferCore::V_TimeCacheInterface
std::vector< TimeCacheInterfacePtr > V_TimeCacheInterface
tf2::BufferCore::TransformableRequest::request_handle
TransformableRequestHandle request_handle
Definition: buffer_core.h:347
tf2::BufferCore::_validateFrameId
CompactFrameID _validateFrameId(const char *function_name_arg, const std::string &frame_id) const
tf2::BufferCore::addTransformableCallback
TransformableCallbackHandle addTransformableCallback(const TransformableCallback &cb)
tf2::BufferCore::TransformableRequest::cb_handle
TransformableCallbackHandle cb_handle
Definition: buffer_core.h:348
tf2::BufferCore::allFramesAsStringNoLock
std::string allFramesAsStringNoLock() const
tf2::BufferCore::~BufferCore
virtual ~BufferCore(void)
tf2::BufferCore::V_TransformableRequest
std::vector< TransformableRequest > V_TransformableRequest
tf2::BufferCore::setTransform
bool setTransform(const geometry_msgs::TransformStamped &transform, const std::string &authority, bool is_static=false)
tf2::BufferCore::getFrame
TimeCacheInterfacePtr getFrame(CompactFrameID c_frame_id) const
tf2::BufferCore::_addTransformsChangedListener
boost::signals2::connection _addTransformsChangedListener(boost::function< void(void)> callback)
tf2::BufferCore::MAX_GRAPH_DEPTH
static const uint32_t MAX_GRAPH_DEPTH
Maximum graph search depth (deeper graphs will be assumed to have loops)
Definition: buffer_core.h:94
tf2::BufferCore::lookupTransform
geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const ros::Time &target_time, const std::string &source_frame, const ros::Time &source_time, const std::string &fixed_frame) const
tf2::BufferCore::transformable_requests_mutex_
boost::mutex transformable_requests_mutex_
tf2::BufferCore::allFramesAsYAML
std::string allFramesAsYAML() const
tf2::BufferCore::transformable_callbacks_counter_
uint32_t transformable_callbacks_counter_
Definition: buffer_core.h:341
tf2::BufferCore::_removeTransformsChangedListener
void _removeTransformsChangedListener(boost::signals2::connection c)
tf2::BufferCore::TransformableRequest::time
ros::Time time
Definition: buffer_core.h:346
tf2::BufferCore::walkToTopParent
int walkToTopParent(F &f, ros::Time time, CompactFrameID target_id, CompactFrameID source_id, std::string *error_string) const
tf2::BufferCore::_getLatestCommonTime
int _getLatestCommonTime(CompactFrameID target_frame, CompactFrameID source_frame, ros::Time &time, std::string *error_string) const
tf2::BufferCore::M_TransformableCallback
boost::unordered_map< TransformableCallbackHandle, TransformableCallback > M_TransformableCallback
tf2::BufferCore::_lookupFrameNumber
CompactFrameID _lookupFrameNumber(const std::string &frameid_str) const
tf2::TransformFailure
TransformFailure
tf2::BufferCore::allFramesAsString
std::string allFramesAsString() const
tf2::BufferCore::getCacheLength
ros::Duration getCacheLength()
tf2::TestBufferCore::_lookupFrameString
const std::string & _lookupFrameString(BufferCore &buffer, CompactFrameID frame_id_num) const
tf2::BufferCore::canTransformNoLock
bool canTransformNoLock(CompactFrameID target_id, CompactFrameID source_id, const ros::Time &time, std::string *error_msg) const
tf2::BufferCore::frameIDs_reverse
std::vector< std::string > frameIDs_reverse
A map from CompactFrameID frame_id_numbers to string for debugging and output.
Definition: buffer_core.h:331
CompactFrameID
uint32_t CompactFrameID
tf2::BufferCore::_chainAsVector
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
tf2::BufferCore::transformable_callbacks_
M_TransformableCallback transformable_callbacks_
Definition: buffer_core.h:340
tf2::BufferCore::_getFrameStrings
void _getFrameStrings(std::vector< std::string > &ids) const
tf2::TransformableRequestHandle
uint64_t TransformableRequestHandle
tf2::BufferCore::clear
void clear()
tf2::BufferCore::isUsingDedicatedThread
bool isUsingDedicatedThread() const
tf2::BufferCore::TransformsChangedSignal
boost::signals2::signal< void(void)> TransformsChangedSignal
tf2::BufferCore::cache_time_
ros::Duration cache_time_
How long to cache transform history.
Definition: buffer_core.h:337
tf2::BufferCore::frame_mutex_
boost::mutex frame_mutex_
transform_storage.h
tf2::BufferCore::frameIDs_
M_StringToCompactFrameID frameIDs_
Definition: buffer_core.h:329
tf2::BufferCore::_allFramesAsDot
std::string _allFramesAsDot() const
tf2::BufferCore::canTransform
bool canTransform(const std::string &target_frame, const ros::Time &target_time, const std::string &source_frame, const ros::Time &source_time, const std::string &fixed_frame, std::string *error_msg=NULL) const
tf2::TimeCacheInterface
Definition: time_cache.h:57
tf2::BufferCore::_frameExists
bool _frameExists(const std::string &frame_id_str) const
tf2::BufferCore::cancelTransformableRequest
void cancelTransformableRequest(TransformableRequestHandle handle)
tf2::BufferCore::M_StringToCompactFrameID
boost::unordered_map< std::string, CompactFrameID > M_StringToCompactFrameID
tf2::BufferCore::_lookupOrInsertFrameNumber
CompactFrameID _lookupOrInsertFrameNumber(const std::string &frameid_str)
tf2::BufferCore::lookupFrameString
const std::string & lookupFrameString(CompactFrameID frame_id_num) const
tf2::BufferCore::validateFrameId
CompactFrameID validateFrameId(const char *function_name_arg, const std::string &frame_id) const
tf2::BufferCore::transformable_requests_
V_TransformableRequest transformable_requests_
Definition: buffer_core.h:355
tf2::BufferCore::frame_authority_
std::map< CompactFrameID, std::string > frame_authority_
A map to lookup the most recent authority for a given frame.
Definition: buffer_core.h:333
tf2::P_TimeAndFrameID
std::pair< ros::Time, CompactFrameID > P_TimeAndFrameID
Definition: time_cache.h:55
tf2::BufferCore::frames_
V_TimeCacheInterface frames_
Definition: buffer_core.h:322
ros::Time
sick_scan_xd_api_test.c
c
Definition: sick_scan_xd_api_test.py:445
tf2::TestBufferCore::_walkToTopParent
int _walkToTopParent(BufferCore &buffer, ros::Time time, CompactFrameID target_id, CompactFrameID source_id, std::string *error_string, std::vector< CompactFrameID > *frame_chain) const
tf2::BufferCore::createConnectivityErrorString
void createConnectivityErrorString(CompactFrameID source_frame, CompactFrameID target_frame, std::string *out) const
tf2::BufferCore::DEFAULT_CACHE_TIME
static const int DEFAULT_CACHE_TIME
The default amount of time to cache data in seconds.
Definition: buffer_core.h:93
TransformStamped.h
tf2::BufferCore::addTransformableRequest
TransformableRequestHandle addTransformableRequest(TransformableCallbackHandle handle, const std::string &target_frame, const std::string &source_frame, ros::Time time)
tf2
tf2::BufferCore::lookupOrInsertFrameNumber
CompactFrameID lookupOrInsertFrameNumber(const std::string &frameid_str)
tf2::BufferCore::TransformableRequest::source_string
std::string source_string
Definition: buffer_core.h:352
sick_scan_base.h
tf2::BufferCore::BufferCore
BufferCore(ros::Duration cache_time_=ros::Duration(DEFAULT_CACHE_TIME))
tf2::BufferCore::TransformableRequest::source_id
CompactFrameID source_id
Definition: buffer_core.h:350
target_frame
std::string target_frame
tf2::BufferCore::using_dedicated_thread_
bool using_dedicated_thread_
Definition: buffer_core.h:415
tf2::BufferCore::canTransformInternal
bool canTransformInternal(CompactFrameID target_id, CompactFrameID source_id, const ros::Time &time, std::string *error_msg) const
tf2::BufferCore::removeTransformableCallback
void removeTransformableCallback(TransformableCallbackHandle handle)
tf2::BufferCore::transformable_callbacks_mutex_
boost::mutex transformable_callbacks_mutex_
tf2::BufferCore::lookupFrameNumber
CompactFrameID lookupFrameNumber(const std::string &frameid_str) const
ros::Duration
geometry_msgs::TransformStamped_
Definition: TransformStamped.h:25
tf2::TransformableResult
TransformableResult
tf2::BufferCore::_getParent
bool _getParent(const std::string &frame_id, ros::Time time, std::string &parent) const
tf2::TransformableCallbackHandle
uint32_t TransformableCallbackHandle
tf2::BufferCore::TransformableRequest::target_string
std::string target_string
Definition: buffer_core.h:351
tf2::TransformAvailable
TransformAvailable
callback
void callback(const sick_scan_xd::RadarScan::ConstPtr &oa)
Definition: radar_object_marker.cpp:157


sick_scan_xd
Author(s): Michael Lehning , Jochen Sprickerhof , Martin Günther
autogenerated on Fri Oct 25 2024 02:47:07