Public Member Functions | Protected Attributes | Private Attributes | List of all members
cras::InterruptibleTFBuffer Class Reference

Provides overrides of canTransform() that can be interrupted. Normally, canTransform() waits until transform is available, timeout is reached (which may be never in paused simulation), time jumps backwards or ros::ok() returns false. This buffer adds another option of interrupting the call. It also allows "wrapping around" another buffer that does not support this interruptibility and add this ability to it. More...

#include <interruptible_buffer.h>

Inheritance diagram for cras::InterruptibleTFBuffer:
Inheritance graph
[legend]

Public Member Functions

::std::string allFramesAsString () const
 A way to see what frames have been cached. Useful for debugging. More...
 
::std::string allFramesAsYAML () const
 Backwards compatibility for #84. More...
 
::std::string allFramesAsYAML (double current_time) const
 A way to see what frames have been cached in yaml format. Useful for debugging tools. More...
 
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, ::ros::Duration timeout) const
 Test if a transform is possible. More...
 
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, ::ros::Duration timeout, ::std::string *errstr) const override
 
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=nullptr) const
 Test if a transform is possible. More...
 
bool canTransform (const ::std::string &target_frame, const ::std::string &source_frame, const ::ros::Time &time, ::ros::Duration timeout) const
 Test if a transform is possible. More...
 
bool canTransform (const ::std::string &target_frame, const ::std::string &source_frame, const ::ros::Time &time, ::ros::Duration timeout, ::std::string *errstr) const override
 
bool canTransform (const ::std::string &target_frame, const ::std::string &source_frame, const ::ros::Time &time, ::std::string *error_msg=nullptr) const
 Test if a transform is possible. More...
 
void clear ()
 Clear all data. More...
 
::ros::Duration getCacheLength ()
 Get the duration over which this transformer will cache. More...
 
::tf2::BufferCoregetRawBuffer ()
 Get the raw tf2::BufferCore that actually stores the transforms. More...
 
const ::tf2::BufferCoregetRawBuffer () const
 Get the raw tf2::BufferCore that actually stores the transforms. More...
 
 InterruptibleTFBuffer (const ::ros::Duration &cacheTime={::tf2::BufferCore::DEFAULT_CACHE_TIME, 0})
 Create the buffer. More...
 
 InterruptibleTFBuffer (const ::std::shared_ptr<::tf2::BufferCore > &parentBuffer)
 Create the buffer that relays lookups to the given parentBuffer and adds the interruptible behavior to it. Cache duration is the same as in parentBuffer. Only getCacheLength(), canTransform() and lookupTransform() methods are valid on this buffer in this mode. Any modifications/tf listeners should be done on the parent buffer. More...
 
::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
 Get the transform between two frames by frame ID assuming fixed frame. More...
 
::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 ::ros::Duration timeout) const override
 
::geometry_msgs::TransformStamped lookupTransform (const ::std::string &target_frame, const ::std::string &source_frame, const ::ros::Time &time) const
 Get the transform between two frames by frame ID. More...
 
::geometry_msgs::TransformStamped lookupTransform (const ::std::string &target_frame, const ::std::string &source_frame, const ::ros::Time &time, const ::ros::Duration timeout) const override
 
bool ok () const override
 Whether it is OK to continue. If false, all pending lookups should stop as soon as possible. More...
 
virtual void requestStop ()
 Request all pending lookups to stop. After calling this, ok() should return false. More...
 
bool setCanTransformPollingScale (double scale)
 Set the scale by which canTransform() timeout is multiplied to determine the transform polling rate. More...
 
bool setMinPollingDuration (const ::ros::Duration &duration)
 Set minimum duration of a pause between two transform polls. More...
 
bool setTransform (const ::geometry_msgs::TransformStamped &transform, const ::std::string &authority, bool is_static=false)
 Add transform information to the tf data structure. More...
 
template<class A , class B >
B & transform (const A &in, B &out, const ::std::string &target_frame, ::ros::Duration timeout={0, 0}) const
 Transform an input into the target frame and convert to a specified output type. It is templated on two types: the type of the input object and the type of the transformed output. For example, the template types could be Transform, Pose, Vector, or Quaternion messages type (as defined in geometry_msgs). The function will calculate the transformation and then convert the result into the specified output type. Compilation will fail if a known conversion does not exist bewteen the two template parameters. More...
 
template<class A , class B >
B & transform (const A &in, B &out, const ::std::string &target_frame, const ::ros::Time &target_time, const ::std::string &fixed_frame, ::ros::Duration timeout={0, 0}) const
 Transform an input into the target frame and convert to a specified output type (advanced). It is templated on two types: the type of the input object and the type of the transformed output. For example, the template type could be a Transform, Pose, Vector, or Quaternion message type (as defined in geometry_msgs). The function will calculate the transformation and then convert the result into the specified output type. Compilation will fail if a known conversion does not exist bewteen the two template parameters. This function follows the advanced API, which allows transforming between different time points, and specifying a fixed frame that does not varying in time. More...
 
template<class T >
transform (const T &in, const ::std::string &target_frame, ::ros::Duration timeout={0, 0}) const
 Transform an input into the target frame. This function is templated and can take as input any valid mathematical object that tf knows how to apply a transform to, by way of the templated math conversions interface. For example, the template type could be a Transform, Pose, Vector, or Quaternion message type (as defined in geometry_msgs). More...
 
template<class T >
transform (const T &in, const ::std::string &target_frame, const ::ros::Time &target_time, const ::std::string &fixed_frame, ::ros::Duration timeout={0, 0}) const
 Transform an input into the target frame (advanced). This function is templated and can take as input any valid mathematical object that tf knows how to apply a transform to, by way of the templated math conversions interface. For example, the template type could be a Transform, Pose, Vector, or Quaternion message type (as defined in geometry_msgs). This function follows the advanced API, which allows transforming between different time points, and specifying a fixed frame that does not varying in time. More...
 
template<class T >
T & transform (const T &in, T &out, const ::std::string &target_frame, ::ros::Duration timeout={0, 0}) const
 Transform an input into the target frame. This function is templated and can take as input any valid mathematical object that tf knows how to apply a transform to, by way of the templated math conversions interface. For example, the template type could be a Transform, Pose, Vector, or Quaternion message type (as defined in geometry_msgs). More...
 
template<class T >
T & transform (const T &in, T &out, const ::std::string &target_frame, const ::ros::Time &target_time, const ::std::string &fixed_frame, ::ros::Duration timeout={0, 0}) const
 Transform an input into the target frame (advanced). This function is templated and can take as input any valid mathematical object that tf knows how to apply a transform to, by way of the templated math conversions interface. For example, the template type could be a Transform, Pose, Vector, or Quaternion message type (as defined in geometry_msgs). This function follows the advanced API, which allows transforming between different time points, and specifying a fixed frame that does not varying in time. More...
 
 ~InterruptibleTFBuffer () override
 Destroys the class. Waits until a running canTransform() call is finished. More...
 
- Public Member Functions inherited from cras::InterruptibleSleepInterface
 InterruptibleSleepInterface ()
 
virtual bool sleep (const ::ros::Duration &duration) const
 Sleep for the given duration or until ok() returns false. More...
 
virtual ~InterruptibleSleepInterface ()
 Destroy the object waiting for a pending sleep() call to finish. More...
 

Protected Attributes

double canTransformPollingScale {0.01}
 canTransform() timeout is multiplied by this scale and polling for the transform is done in these time steps. More...
 
::ros::Duration minPollingDuration {0, 1000000}
 Minimum duration of a pause between two transform polls. If timeout * canTransformPollingScale would be smaller than this value, this value will be used instead to prevent too frequent queries. More...
 
const ::std::shared_ptr<::tf2::BufferCoreparentBuffer {nullptr}
 If not null, this class relays all lookups to parentBuffer. More...
 
- Protected Attributes inherited from cras::InterruptibleSleepInterface
::ros::WallDuration pollDuration {0, 1000000}
 How long to wait between querying the ok() status and other conditions. More...
 

Private Attributes

mutable ::cras::ReverseSemaphore callbackSemaphore
 Reverse semaphore guarding that the object is not destroyed before all pending callbacks finish. At the start of each callback, the semaphore is increased, and at the end of the callback, it is decreased. The destructor of this class will block until the semaphore reaches zero. More...
 
const ::std::shared_ptr<::cras::InterruptibleTFBufferinterruptibleParentBuffer {nullptr}
 If parentBuffer is set and it is an InterruptibleTFBuffer, its dynamic cast to this type is stored here. More...
 
bool isOk {true}
 True until requestStop() is called. More...
 

Additional Inherited Members

- Protected Types inherited from tf2::BufferCore
typedef boost::function< void(TransformableRequestHandle request_handle, const std::string &target_frame, const std::string &source_frame, ros::Time time, TransformableResult result)> TransformableCallback
 
- Protected Member Functions inherited from tf2_ros::Buffer
 Buffer (ros::Duration cache_time=ros::Duration(BufferCore::DEFAULT_CACHE_TIME), bool debug=false)
 
virtual 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, const ros::Duration timeout, std::string *errstr=NULL) const
 
virtual bool canTransform (const std::string &target_frame, const std::string &source_frame, const ros::Time &target_time, const ros::Duration timeout, std::string *errstr=NULL) const
 
virtual 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 ros::Duration timeout) const
 
virtual geometry_msgs::TransformStamped lookupTransform (const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration timeout) const
 
- Protected Member Functions inherited from tf2_ros::BufferInterface
B & transform (const A &in, B &out, const std::string &target_frame, const ros::Time &target_time, const std::string &fixed_frame, ros::Duration timeout=ros::Duration(0.0)) const
 
B & transform (const A &in, B &out, const std::string &target_frame, ros::Duration timeout=ros::Duration(0.0)) const
 
transform (const T &in, const std::string &target_frame, const ros::Time &target_time, const std::string &fixed_frame, ros::Duration timeout=ros::Duration(0.0)) const
 
transform (const T &in, const std::string &target_frame, ros::Duration timeout=ros::Duration(0.0)) const
 
T & transform (const T &in, T &out, const std::string &target_frame, const ros::Time &target_time, const std::string &fixed_frame, ros::Duration timeout=ros::Duration(0.0)) const
 
T & transform (const T &in, T &out, const std::string &target_frame, ros::Duration timeout=ros::Duration(0.0)) const
 
- Protected Member Functions inherited from tf2::BufferCore
boost::signals2::connection _addTransformsChangedListener (boost::function< void(void)> callback)
 
std::string _allFramesAsDot () const
 
std::string _allFramesAsDot (double current_time) const
 
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
 
bool _frameExists (const std::string &frame_id_str) const
 
void _getFrameStrings (std::vector< std::string > &ids) const
 
int _getLatestCommonTime (CompactFrameID target_frame, CompactFrameID source_frame, ros::Time &time, std::string *error_string) const
 
bool _getParent (const std::string &frame_id, ros::Time time, std::string &parent) const
 
CompactFrameID _lookupFrameNumber (const std::string &frameid_str) const
 
CompactFrameID _lookupOrInsertFrameNumber (const std::string &frameid_str)
 
void _removeTransformsChangedListener (boost::signals2::connection c)
 
CompactFrameID _validateFrameId (const char *function_name_arg, const std::string &frame_id) const
 
TransformableCallbackHandle addTransformableCallback (const TransformableCallback &cb)
 
TransformableRequestHandle addTransformableRequest (TransformableCallbackHandle handle, const std::string &target_frame, const std::string &source_frame, ros::Time time)
 
std::string allFramesAsString () const
 
std::string allFramesAsYAML () const
 
std::string allFramesAsYAML (double current_time) const
 
 BufferCore (ros::Duration cache_time_=ros::Duration(DEFAULT_CACHE_TIME))
 
void cancelTransformableRequest (TransformableRequestHandle handle)
 
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
 
bool canTransform (const std::string &target_frame, const std::string &source_frame, const ros::Time &time, std::string *error_msg=NULL) const
 
void clear ()
 
ros::Duration getCacheLength ()
 
bool isUsingDedicatedThread () const
 
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
 
geometry_msgs::TransformStamped lookupTransform (const std::string &target_frame, const std::string &source_frame, const ros::Time &time) const
 
void removeTransformableCallback (TransformableCallbackHandle handle)
 
bool setTransform (const geometry_msgs::TransformStamped &transform, const std::string &authority, bool is_static=false)
 
void setUsingDedicatedThread (bool value)
 
virtual ~BufferCore (void)
 
- Protected Member Functions inherited from cras::InterruptibleSleepInterface
 InterruptibleSleepInterface ()
 
virtual bool sleep (const ::ros::Duration &duration) const
 Sleep for the given duration or until ok() returns false. More...
 
virtual ~InterruptibleSleepInterface ()
 Destroy the object waiting for a pending sleep() call to finish. More...
 
- Static Protected Attributes inherited from tf2::BufferCore
static const int DEFAULT_CACHE_TIME
 
static const uint32_t MAX_GRAPH_DEPTH
 

Detailed Description

Provides overrides of canTransform() that can be interrupted. Normally, canTransform() waits until transform is available, timeout is reached (which may be never in paused simulation), time jumps backwards or ros::ok() returns false. This buffer adds another option of interrupting the call. It also allows "wrapping around" another buffer that does not support this interruptibility and add this ability to it.

Note
In the "wrapping around" mode, do not call any other functions than canTransform() and lookupTransform(). Other functions will return wrong results.
The buffer is partly concurrent. This means canTransform() and lookupTransform() calls can be interleaved, but in the end all of them share the same tf2::BufferCore which locks the frames mutex in canTransform()/lookupTransform(). But they access the BufferCore only from time to time in some polling intervals, so concurrency should be good in the end.
The destructor of this class does not finish until no canTransform() or lookupTransform() call is being executed. Call requestStop() to instruct the buffer to reject any new requests and finish the ongoing ones as soon as possible, most probably resulting in failures.

Definition at line 42 of file interruptible_buffer.h.

Constructor & Destructor Documentation

◆ InterruptibleTFBuffer() [1/2]

cras::InterruptibleTFBuffer::InterruptibleTFBuffer ( const ::ros::Duration cacheTime = {::tf2::BufferCore::DEFAULT_CACHE_TIME, 0})
explicit

Create the buffer.

Parameters
[in]cacheTimeHow long to keep a history of transforms

◆ InterruptibleTFBuffer() [2/2]

cras::InterruptibleTFBuffer::InterruptibleTFBuffer ( const ::std::shared_ptr<::tf2::BufferCore > &  parentBuffer)
explicit

Create the buffer that relays lookups to the given parentBuffer and adds the interruptible behavior to it. Cache duration is the same as in parentBuffer. Only getCacheLength(), canTransform() and lookupTransform() methods are valid on this buffer in this mode. Any modifications/tf listeners should be done on the parent buffer.

Parameters
[in]parentBufferThe buffer to relay lookups to.

◆ ~InterruptibleTFBuffer()

cras::InterruptibleTFBuffer::~InterruptibleTFBuffer ( )
override

Destroys the class. Waits until a running canTransform() call is finished.

Member Function Documentation

◆ allFramesAsString()

::std::string cras::InterruptibleTFBuffer::allFramesAsString ( ) const

A way to see what frames have been cached. Useful for debugging.

◆ allFramesAsYAML() [1/2]

::std::string cras::InterruptibleTFBuffer::allFramesAsYAML ( ) const

Backwards compatibility for #84.

◆ allFramesAsYAML() [2/2]

::std::string cras::InterruptibleTFBuffer::allFramesAsYAML ( double  current_time) const

A way to see what frames have been cached in yaml format. Useful for debugging tools.

◆ canTransform() [1/6]

bool cras::InterruptibleTFBuffer::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,
::ros::Duration  timeout 
) const

Test if a transform is possible.

Parameters
[in]target_frameThe frame into which to transform.
[in]target_timeThe time into which to transform.
[in]source_frameThe frame from which to transform.
[in]source_timeThe time from which to transform.
[in]fixed_frameThe frame in which to treat the transform as constant in time.
[in]timeoutHow long to block before failing.
Returns
True if the transform is possible, false otherwise.

◆ canTransform() [2/6]

bool cras::InterruptibleTFBuffer::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,
::ros::Duration  timeout,
::std::string *  errstr 
) const
override

◆ canTransform() [3/6]

bool cras::InterruptibleTFBuffer::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 = nullptr 
) const

Test if a transform is possible.

Parameters
[in]target_frameThe frame into which to transform
[in]target_timeThe time into which to transform
[in]source_frameThe frame from which to transform
[in]source_timeThe time from which to transform
[in]fixed_frameThe frame in which to treat the transform as constant in time
[out]error_msgA pointer to a string which will be filled with why the transform failed, if not NULL.
Returns
True if the transform is possible, false otherwise.

◆ canTransform() [4/6]

bool cras::InterruptibleTFBuffer::canTransform ( const ::std::string &  target_frame,
const ::std::string &  source_frame,
const ::ros::Time time,
::ros::Duration  timeout 
) const

Test if a transform is possible.

Parameters
[in]target_frameThe frame into which to transform.
[in]source_frameThe frame from which to transform.
[in]timeThe time at which to transform.
[in]timeoutHow long to block before failing.
Returns
True if the transform is possible, false otherwise.

◆ canTransform() [5/6]

bool cras::InterruptibleTFBuffer::canTransform ( const ::std::string &  target_frame,
const ::std::string &  source_frame,
const ::ros::Time time,
::ros::Duration  timeout,
::std::string *  errstr 
) const
override

◆ canTransform() [6/6]

bool cras::InterruptibleTFBuffer::canTransform ( const ::std::string &  target_frame,
const ::std::string &  source_frame,
const ::ros::Time time,
::std::string *  error_msg = nullptr 
) const

Test if a transform is possible.

Parameters
[in]target_frameThe frame into which to transform
[in]source_frameThe frame from which to transform
[in]timeThe time at which to transform
[out]error_msgA pointer to a string which will be filled with why the transform failed, if not NULL.
Returns
True if the transform is possible, false otherwise.

◆ clear()

void cras::InterruptibleTFBuffer::clear ( )

Clear all data.

◆ getCacheLength()

::ros::Duration cras::InterruptibleTFBuffer::getCacheLength ( )

Get the duration over which this transformer will cache.

◆ getRawBuffer() [1/2]

::tf2::BufferCore& cras::InterruptibleTFBuffer::getRawBuffer ( )

Get the raw tf2::BufferCore that actually stores the transforms.

Returns
The raw buffer.

◆ getRawBuffer() [2/2]

const ::tf2::BufferCore& cras::InterruptibleTFBuffer::getRawBuffer ( ) const

Get the raw tf2::BufferCore that actually stores the transforms.

Returns
The raw buffer.

◆ lookupTransform() [1/4]

::geometry_msgs::TransformStamped cras::InterruptibleTFBuffer::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

Get the transform between two frames by frame ID assuming fixed frame.

Parameters
[in]target_frameThe frame to which data should be transformed
[in]target_timeThe time to which the data should be transformed. (0 will get the latest)
[in]source_frameThe frame where the data originated
[in]source_timeThe time at which the source_frame should be evaluated. (0 will get the latest)
[in]fixed_frameThe frame in which to assume the transform is constant in time.
Returns
The transform between the frames.
Exceptions
tf2::LookupException,tf2::ConnectivityException,tf2::ExtrapolationException,tf2::InvalidArgumentException

◆ lookupTransform() [2/4]

::geometry_msgs::TransformStamped cras::InterruptibleTFBuffer::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 ::ros::Duration  timeout 
) const
override

◆ lookupTransform() [3/4]

::geometry_msgs::TransformStamped cras::InterruptibleTFBuffer::lookupTransform ( const ::std::string &  target_frame,
const ::std::string &  source_frame,
const ::ros::Time time 
) const

Get the transform between two frames by frame ID.

Parameters
[in]target_frameThe frame to which data should be transformed
[in]source_frameThe frame where the data originated
[in]timeThe time at which the value of the transform is desired. (0 will get the latest)
Returns
The transform between the frames.
Exceptions
tf2::LookupException,tf2::ConnectivityException,tf2::ExtrapolationException,tf2::InvalidArgumentException

◆ lookupTransform() [4/4]

::geometry_msgs::TransformStamped cras::InterruptibleTFBuffer::lookupTransform ( const ::std::string &  target_frame,
const ::std::string &  source_frame,
const ::ros::Time time,
const ::ros::Duration  timeout 
) const
override

◆ ok()

bool cras::InterruptibleTFBuffer::ok ( ) const
overridevirtual

Whether it is OK to continue. If false, all pending lookups should stop as soon as possible.

Returns
Whether it is OK to continue.

Reimplemented from cras::InterruptibleSleepInterface.

◆ requestStop()

virtual void cras::InterruptibleTFBuffer::requestStop ( )
virtual

Request all pending lookups to stop. After calling this, ok() should return false.

◆ setCanTransformPollingScale()

bool cras::InterruptibleTFBuffer::setCanTransformPollingScale ( double  scale)

Set the scale by which canTransform() timeout is multiplied to determine the transform polling rate.

Parameters
scaleThe scale to set. Must be between 0 and 1.
Returns
Whether the given scale was set. Returns false if an invalid scale was provided.

◆ setMinPollingDuration()

bool cras::InterruptibleTFBuffer::setMinPollingDuration ( const ::ros::Duration duration)

Set minimum duration of a pause between two transform polls.

Parameters
[in]durationThe minimum duration. It has to be positive.
Returns
Whether the given duration is valid and was set.

◆ setTransform()

bool cras::InterruptibleTFBuffer::setTransform ( const ::geometry_msgs::TransformStamped &  transform,
const ::std::string &  authority,
bool  is_static = false 
)

Add transform information to the tf data structure.

Parameters
[in]transformThe transform to store
[in]authorityThe source of the information for this transform
[in]is_staticRecord this transform as a static transform. It will be good across all time. (This cannot be changed after the first call.)
Returns
True unless an error occurred.

◆ transform() [1/6]

template<class A , class B >
B& cras::InterruptibleTFBuffer::transform ( const A &  in,
B &  out,
const ::std::string &  target_frame,
::ros::Duration  timeout = {0, 0} 
) const
inline

Transform an input into the target frame and convert to a specified output type. It is templated on two types: the type of the input object and the type of the transformed output. For example, the template types could be Transform, Pose, Vector, or Quaternion messages type (as defined in geometry_msgs). The function will calculate the transformation and then convert the result into the specified output type. Compilation will fail if a known conversion does not exist bewteen the two template parameters.

Template Parameters
AThe type of the object to transform.
BThe type of the transformed output.
Parameters
[in]inThe object to transform
[out]outThe transformed output, converted to the specified type.
[in]target_frameThe string identifer for the frame to transform into.
[in]timeoutHow long to wait for the target frame. Default value is zero (no blocking).
Returns
The transformed output, converted to the specified type.

Definition at line 200 of file interruptible_buffer.h.

◆ transform() [2/6]

template<class A , class B >
B& cras::InterruptibleTFBuffer::transform ( const A &  in,
B &  out,
const ::std::string &  target_frame,
const ::ros::Time target_time,
const ::std::string &  fixed_frame,
::ros::Duration  timeout = {0, 0} 
) const
inline

Transform an input into the target frame and convert to a specified output type (advanced). It is templated on two types: the type of the input object and the type of the transformed output. For example, the template type could be a Transform, Pose, Vector, or Quaternion message type (as defined in geometry_msgs). The function will calculate the transformation and then convert the result into the specified output type. Compilation will fail if a known conversion does not exist bewteen the two template parameters. This function follows the advanced API, which allows transforming between different time points, and specifying a fixed frame that does not varying in time.

Template Parameters
AThe type of the object to transform.
BThe type of the transformed output.
Parameters
[in]inThe object to transform
[in]outThe transformed output, converted to the specified output type.
[in]target_frameThe string identifer for the frame to transform into.
[in]target_timeThe time into which to transform
[in]fixed_frameThe frame in which to treat the transform as constant in time.
[in]timeoutHow long to wait for the target frame. Default value is zero (no blocking).
Returns
The transformed output, converted to the specified output type.

Definition at line 272 of file interruptible_buffer.h.

◆ transform() [3/6]

template<class T >
T cras::InterruptibleTFBuffer::transform ( const T &  in,
const ::std::string &  target_frame,
::ros::Duration  timeout = {0, 0} 
) const
inline

Transform an input into the target frame. This function is templated and can take as input any valid mathematical object that tf knows how to apply a transform to, by way of the templated math conversions interface. For example, the template type could be a Transform, Pose, Vector, or Quaternion message type (as defined in geometry_msgs).

Template Parameters
TThe type of the object to transform.
Parameters
[in]inThe object to transform.
[in]target_frameThe string identifer for the frame to transform into.
[in]timeoutHow long to wait for the target frame. Default value is zero (no blocking).
Returns
The transformed output.

Definition at line 176 of file interruptible_buffer.h.

◆ transform() [4/6]

template<class T >
T cras::InterruptibleTFBuffer::transform ( const T &  in,
const ::std::string &  target_frame,
const ::ros::Time target_time,
const ::std::string &  fixed_frame,
::ros::Duration  timeout = {0, 0} 
) const
inline

Transform an input into the target frame (advanced). This function is templated and can take as input any valid mathematical object that tf knows how to apply a transform to, by way of the templated math conversions interface. For example, the template type could be a Transform, Pose, Vector, or Quaternion message type (as defined in geometry_msgs). This function follows the advanced API, which allows transforming between different time points, and specifying a fixed frame that does not varying in time.

Template Parameters
TThe type of the object to transform.
Parameters
[in]inThe object to transform
[in]target_frameThe string identifer for the frame to transform into.
[in]target_timeThe time into which to transform
[in]fixed_frameThe frame in which to treat the transform as constant in time.
[in]timeoutHow long to wait for the target frame. Default value is zero (no blocking).
Returns
The transformed output.

Definition at line 244 of file interruptible_buffer.h.

◆ transform() [5/6]

template<class T >
T& cras::InterruptibleTFBuffer::transform ( const T &  in,
T &  out,
const ::std::string &  target_frame,
::ros::Duration  timeout = {0, 0} 
) const
inline

Transform an input into the target frame. This function is templated and can take as input any valid mathematical object that tf knows how to apply a transform to, by way of the templated math conversions interface. For example, the template type could be a Transform, Pose, Vector, or Quaternion message type (as defined in geometry_msgs).

Template Parameters
TThe type of the object to transform.
Parameters
[in]inThe object to transform
[out]outThe transformed output, preallocated by the caller.
[in]target_frameThe string identifer for the frame to transform into.
[in]timeoutHow long to wait for the target frame. Default value is zero (no blocking).

Definition at line 159 of file interruptible_buffer.h.

◆ transform() [6/6]

template<class T >
T& cras::InterruptibleTFBuffer::transform ( const T &  in,
T &  out,
const ::std::string &  target_frame,
const ::ros::Time target_time,
const ::std::string &  fixed_frame,
::ros::Duration  timeout = {0, 0} 
) const
inline

Transform an input into the target frame (advanced). This function is templated and can take as input any valid mathematical object that tf knows how to apply a transform to, by way of the templated math conversions interface. For example, the template type could be a Transform, Pose, Vector, or Quaternion message type (as defined in geometry_msgs). This function follows the advanced API, which allows transforming between different time points, and specifying a fixed frame that does not varying in time.

Template Parameters
TThe type of the object to transform.
Parameters
[in]inThe object to transform
[out]outThe transformed output, preallocated by the caller.
[in]target_frameThe string identifer for the frame to transform into.
[in]target_timeThe time into which to transform
[in]fixed_frameThe frame in which to treat the transform as constant in time.
[in]timeoutHow long to wait for the target frame. Default value is zero (no blocking).

Definition at line 221 of file interruptible_buffer.h.

Member Data Documentation

◆ callbackSemaphore

mutable ::cras::ReverseSemaphore cras::InterruptibleTFBuffer::callbackSemaphore
private

Reverse semaphore guarding that the object is not destroyed before all pending callbacks finish. At the start of each callback, the semaphore is increased, and at the end of the callback, it is decreased. The destructor of this class will block until the semaphore reaches zero.

Definition at line 389 of file interruptible_buffer.h.

◆ canTransformPollingScale

double cras::InterruptibleTFBuffer::canTransformPollingScale {0.01}
protected

canTransform() timeout is multiplied by this scale and polling for the transform is done in these time steps.

Definition at line 373 of file interruptible_buffer.h.

◆ interruptibleParentBuffer

const ::std::shared_ptr<::cras::InterruptibleTFBuffer> cras::InterruptibleTFBuffer::interruptibleParentBuffer {nullptr}
private

If parentBuffer is set and it is an InterruptibleTFBuffer, its dynamic cast to this type is stored here.

Definition at line 384 of file interruptible_buffer.h.

◆ isOk

bool cras::InterruptibleTFBuffer::isOk {true}
private

True until requestStop() is called.

Definition at line 381 of file interruptible_buffer.h.

◆ minPollingDuration

::ros::Duration cras::InterruptibleTFBuffer::minPollingDuration {0, 1000000}
protected

Minimum duration of a pause between two transform polls. If timeout * canTransformPollingScale would be smaller than this value, this value will be used instead to prevent too frequent queries.

Definition at line 377 of file interruptible_buffer.h.

◆ parentBuffer

const ::std::shared_ptr<::tf2::BufferCore> cras::InterruptibleTFBuffer::parentBuffer {nullptr}
protected

If not null, this class relays all lookups to parentBuffer.

Definition at line 369 of file interruptible_buffer.h.


The documentation for this class was generated from the following file:


cras_cpp_common
Author(s): Martin Pecka
autogenerated on Tue Nov 26 2024 03:49:04