Class InterruptibleTFBuffer
Defined in File interruptible_buffer.h
Inheritance Relationships
Base Types
protected tf2_ros::Bufferpublic cras::InterruptibleSleepInterface(Struct InterruptibleSleepInterface)
Derived Type
public cras::NodeletAwareTFBuffer(Class NodeletAwareTFBuffer)
Class Documentation
-
class InterruptibleTFBuffer : protected tf2_ros::Buffer, public cras::InterruptibleSleepInterface
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.
Note
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.
Note
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.
Subclassed by cras::NodeletAwareTFBuffer
Public Functions
-
explicit InterruptibleTFBuffer(const ::ros::Duration &cacheTime = {::tf2::BufferCore::DEFAULT_CACHE_TIME, 0})
Create the buffer.
- Parameters:
cacheTime – [in] How long to keep a history of transforms
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:
parentBuffer – [in] The buffer to relay lookups to.
-
~InterruptibleTFBuffer() override
Destroys the class. Waits until a running
canTransform()call is finished.
-
virtual bool ok() const override
Whether it is OK to continue. If false, all pending lookups should stop as soon as possible.
- Returns:
Whether it is OK to continue.
-
virtual void requestStop()
Request all pending lookups to stop. After calling this,
ok()should return false.
-
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, ::ros::Duration timeout) const
Test if a transform is possible.
- Parameters:
target_frame – [in] The frame into which to transform.
source_frame – [in] The frame from which to transform.
time – [in] The time at which to transform.
timeout – [in] How long to block before failing.
- Returns:
True if the transform is possible, false otherwise.
-
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, ::ros::Duration timeout) const
Test if a transform is possible.
- Parameters:
target_frame – [in] The frame into which to transform.
target_time – [in] The time into which to transform.
source_frame – [in] The frame from which to transform.
source_time – [in] The time from which to transform.
fixed_frame – [in] The frame in which to treat the transform as constant in time.
timeout – [in] How long to block before failing.
- Returns:
True if the transform is possible, false otherwise.
-
::geometry_msgs::TransformStamped lookupTransform(const ::std::string &target_frame, const ::std::string &source_frame, const ::ros::Time &time, const ::ros::Duration timeout) const override
-
::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
-
bool setCanTransformPollingScale(double scale)
Set the scale by which
canTransform()timeout is multiplied to determine the transform polling rate.- Parameters:
scale – The scale to set. Must be between 0 and 1.
- Returns:
Whether the given scale was set. Returns false if an invalid scale was provided.
-
bool setMinPollingDuration(const ::ros::Duration &duration)
Set minimum duration of a pause between two transform polls.
- Parameters:
duration – [in] The minimum duration. It has to be positive.
- Returns:
Whether the given duration is valid and was set.
-
::tf2::BufferCore &getRawBuffer()
Get the raw tf2::BufferCore that actually stores the transforms.
- Returns:
The raw buffer.
-
const ::tf2::BufferCore &getRawBuffer() const
Get the raw tf2::BufferCore that actually stores the transforms.
- Returns:
The raw buffer.
-
template<class T>
inline 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).
- Template Parameters:
T – The type of the object to transform.
- Parameters:
in – [in] The object to transform
out – [out] The transformed output, preallocated by the caller.
target_frame – [in] The string identifer for the frame to transform into.
timeout – [in] How long to wait for the target frame. Default value is zero (no blocking).
-
template<class T>
inline 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).
- Template Parameters:
T – The type of the object to transform.
- Parameters:
in – [in] The object to transform.
target_frame – [in] The string identifer for the frame to transform into.
timeout – [in] How long to wait for the target frame. Default value is zero (no blocking).
- Returns:
The transformed output.
-
template<class A, class B>
inline 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.
- Template Parameters:
A – The type of the object to transform.
B – The type of the transformed output.
- Parameters:
in – [in] The object to transform
out – [out] The transformed output, converted to the specified type.
target_frame – [in] The string identifer for the frame to transform into.
timeout – [in] How long to wait for the target frame. Default value is zero (no blocking).
- Returns:
The transformed output, converted to the specified type.
-
template<class T>
inline 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.
- Template Parameters:
T – The type of the object to transform.
- Parameters:
in – [in] The object to transform
out – [out] The transformed output, preallocated by the caller.
target_frame – [in] The string identifer for the frame to transform into.
target_time – [in] The time into which to transform
fixed_frame – [in] The frame in which to treat the transform as constant in time.
timeout – [in] How long to wait for the target frame. Default value is zero (no blocking).
-
template<class T>
inline 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.
- Template Parameters:
T – The type of the object to transform.
- Parameters:
in – [in] The object to transform
target_frame – [in] The string identifer for the frame to transform into.
target_time – [in] The time into which to transform
fixed_frame – [in] The frame in which to treat the transform as constant in time.
timeout – [in] How long to wait for the target frame. Default value is zero (no blocking).
- Returns:
The transformed output.
-
template<class A, class B>
inline 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.
- Template Parameters:
A – The type of the object to transform.
B – The type of the transformed output.
- Parameters:
in – [in] The object to transform
out – [in] The transformed output, converted to the specified output type.
target_frame – [in] The string identifer for the frame to transform into.
target_time – [in] The time into which to transform
fixed_frame – [in] The frame in which to treat the transform as constant in time.
timeout – [in] How long to wait for the target frame. Default value is zero (no blocking).
- Returns:
The transformed output, converted to the specified output type.
-
::ros::Duration getCacheLength()
Get the duration over which this transformer will cache.
-
void clear()
Clear all data.
-
bool setTransform(const ::geometry_msgs::TransformStamped &transform, const ::std::string &authority, bool is_static = false)
Add transform information to the tf data structure.
- Parameters:
transform – [in] The transform to store
authority – [in] The source of the information for this transform
is_static – [in] Record 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.
-
::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.
- Parameters:
target_frame – [in] The frame to which data should be transformed
source_frame – [in] The frame where the data originated
time – [in] The time at which the value of the transform is desired. (0 will get the latest)
- Throws:
tf2::LookupException –
- Returns:
The transform between the frames.
-
::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.
- Parameters:
target_frame – [in] The frame to which data should be transformed
target_time – [in] The time to which the data should be transformed. (0 will get the latest)
source_frame – [in] The frame where the data originated
source_time – [in] The time at which the source_frame should be evaluated. (0 will get the latest)
fixed_frame – [in] The frame in which to assume the transform is constant in time.
- Throws:
tf2::LookupException –
- Returns:
The transform between the frames.
-
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.
- Parameters:
target_frame – [in] The frame into which to transform
source_frame – [in] The frame from which to transform
time – [in] The time at which to transform
error_msg – [out] A 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.
-
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.
- Parameters:
target_frame – [in] The frame into which to transform
target_time – [in] The time into which to transform
source_frame – [in] The frame from which to transform
source_time – [in] The time from which to transform
fixed_frame – [in] The frame in which to treat the transform as constant in time
error_msg – [out] A 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.
-
::std::string allFramesAsYAML(double current_time) const
A way to see what frames have been cached in yaml format. Useful for debugging tools.
-
::std::string allFramesAsYAML() const
Backwards compatibility for #84.
-
::std::string allFramesAsString() const
A way to see what frames have been cached. Useful for debugging.
Protected Attributes
-
const ::std::shared_ptr<::tf2::BufferCore> parentBuffer = {nullptr}
If not null, this class relays all lookups to parentBuffer.
-
double canTransformPollingScale = {0.01}
canTransform()timeout is multiplied by this scale and polling for the transform is done in these time steps.
-
::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.
-
explicit InterruptibleTFBuffer(const ::ros::Duration &cacheTime = {::tf2::BufferCore::DEFAULT_CACHE_TIME, 0})