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

#include <nodelet_aware_tf_buffer.h>

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

Public Member Functions

 NodeletAwareTFBuffer (const ::nodelet::Nodelet &nodelet, const ::ros::Duration &cacheTime=::ros::Duration(::tf2::BufferCore::DEFAULT_CACHE_TIME))
 Create the buffer. More...
 
 NodeletAwareTFBuffer (const ::nodelet::Nodelet &nodelet, const ::std::shared_ptr<::tf2::BufferCore > &parentBuffer)
 Create the buffer that relays lookups to the given parentBuffer. More...
 
bool ok () const override
 Whether it is OK to continue sleeping. If false, a pending sleep() should stop as soon as possible. More...
 
 ~NodeletAwareTFBuffer () override
 
- Public Member Functions inherited from cras::InterruptibleTFBuffer
::std::string allFramesAsString () const
 A way to see what frames have been cached. Useful for debugging. 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...
 
::std::string allFramesAsYAML () const
 Backwards compatibility for #84. 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, ::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, ::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, ::std::string *error_msg=nullptr) 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, ::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 ::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
 
::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 ::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...
 
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 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 >
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 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 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...
 
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 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...
 
 ~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

const ::nodelet::Nodeletnodelet
 The stateful nodelet to be aware of. More...
 
- Protected Attributes inherited from cras::InterruptibleTFBuffer
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...
 

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 std::string &source_frame, const ros::Time &target_time, const ros::Duration timeout, std::string *errstr=NULL) const
 
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 geometry_msgs::TransformStamped lookupTransform (const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration timeout) 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
 
- Protected Member Functions inherited from tf2_ros::BufferInterface
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, 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
 
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
 
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
 
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
 
- Protected Member Functions inherited from tf2::BufferCore
boost::signals2::connection _addTransformsChangedListener (boost::function< void(void)> callback)
 
std::string _allFramesAsDot (double current_time) const
 
std::string _allFramesAsDot () 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 (double current_time) const
 
std::string allFramesAsYAML () const
 
 BufferCore (ros::Duration cache_time_=ros::Duration(DEFAULT_CACHE_TIME))
 
void cancelTransformableRequest (TransformableRequestHandle handle)
 
bool canTransform (const std::string &target_frame, const std::string &source_frame, const ros::Time &time, std::string *error_msg=NULL) const
 
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
 
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 correctly end when the nodelet is asked to unload.

See issue https://github.com/ros/geometry2/issues/381 for more details.

Definition at line 27 of file nodelet_aware_tf_buffer.h.

Constructor & Destructor Documentation

◆ NodeletAwareTFBuffer() [1/2]

cras::NodeletAwareTFBuffer::NodeletAwareTFBuffer ( const ::nodelet::Nodelet nodelet,
const ::ros::Duration cacheTime = ::ros::Duration(::tf2::BufferCore::DEFAULT_CACHE_TIME) 
)
explicit

Create the buffer.

Parameters
[in]nodeletThe stateful nodelet to be aware of.
[in]cacheTimeHow long to keep a history of transforms

◆ NodeletAwareTFBuffer() [2/2]

cras::NodeletAwareTFBuffer::NodeletAwareTFBuffer ( const ::nodelet::Nodelet nodelet,
const ::std::shared_ptr<::tf2::BufferCore > &  parentBuffer 
)

Create the buffer that relays lookups to the given parentBuffer.

Parameters
[in]nodeletThe stateful nodelet to be aware of.
[in]parentBufferThe buffer to relay lookups to. It may be null.

◆ ~NodeletAwareTFBuffer()

cras::NodeletAwareTFBuffer::~NodeletAwareTFBuffer ( )
override

Member Function Documentation

◆ ok()

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

Whether it is OK to continue sleeping. If false, a pending sleep() should stop as soon as possible.

Returns
Whether it is OK to continue.
Note
Always override this function as its default implementation returns false (used in case this function is called after the descendant parts of the objects have already been destructed).

Reimplemented from cras::InterruptibleSleepInterface.

Member Data Documentation

◆ nodelet

const ::nodelet::Nodelet& cras::NodeletAwareTFBuffer::nodelet
protected

The stateful nodelet to be aware of.

Definition at line 52 of file nodelet_aware_tf_buffer.h.


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


cras_cpp_common
Author(s): Martin Pecka
autogenerated on Sat Jun 17 2023 02:32:53