Classes | Public Types | Signals | Public Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
rviz::FrameManager Class Reference

Helper class for transforming data into Ogre's world frame (the fixed frame). More...

#include <frame_manager.h>

Inheritance diagram for rviz::FrameManager:
Inheritance graph
[legend]

Classes

struct  CacheEntry
 
struct  CacheKey
 

Public Types

enum  SyncMode { SyncOff = 0, SyncExact, SyncApprox }
 

Signals

void fixedFrameChanged ()
 Emitted whenever the fixed frame changes. More...
 

Public Member Functions

std::string discoverFailureReason (const std::string &frame_id, const ros::Time &stamp, const std::string &caller_id, tf::FilterFailureReason reason)
 Create a description of a transform problem. More...
 
std::string discoverFailureReason (const std::string &frame_id, const ros::Time &stamp, const std::string &caller_id, tf2_ros::FilterFailureReason reason)
 
bool frameHasProblems (const std::string &frame, ros::Time time, std::string &error)
 Check to see if a frame exists in the tf::TransformListener. More...
 
 FrameManager ()
 Default constructor, which will create a tf::TransformListener automatically. More...
 
 FrameManager (boost::shared_ptr< tf::TransformListener > tf)
 Constructor. More...
 
const std::string & getFixedFrame ()
 Return the current fixed frame name. More...
 
bool getPause ()
 
SyncMode getSyncMode ()
 
const std::shared_ptr< tf2_ros::BuffergetTF2BufferPtr ()
 
tf::TransformListenergetTFClient ()
 Return the tf::TransformListener used to receive transform data. More...
 
const boost::shared_ptr< tf::TransformListener > & getTFClientPtr ()
 Return a boost shared pointer to the tf::TransformListener used to receive transform data. More...
 
ros::Time getTime ()
 Get current time, depending on the sync mode. More...
 
template<typename Header >
bool getTransform (const Header &header, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
 Return the pose for a header, relative to the fixed frame, in Ogre classes. More...
 
bool getTransform (const std::string &frame, ros::Time time, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
 Return the pose for a frame relative to the fixed frame, in Ogre classes, at a given time. More...
 
template<class M >
void registerFilterForTransformStatusCheck (tf::MessageFilter< M > *filter, Display *display)
 Connect a tf::MessageFilter's callbacks to success and failure handler functions in this FrameManager. More...
 
template<class M >
void registerFilterForTransformStatusCheck (tf2_ros::MessageFilter< M > *filter, Display *display)
 
void setFixedFrame (const std::string &frame)
 Set the frame to consider "fixed", into which incoming data is transformed. More...
 
void setPause (bool pause)
 Enable/disable pause mode. More...
 
void setSyncMode (SyncMode mode)
 Set synchronization mode (off/exact/approximate) More...
 
void syncTime (ros::Time time)
 Synchronize with given time. More...
 
template<typename Header >
bool transform (const Header &header, const geometry_msgs::Pose &pose, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
 Transform a pose from a frame into the fixed frame. More...
 
bool transform (const std::string &frame, ros::Time time, const geometry_msgs::Pose &pose, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
 Transform a pose from a frame into the fixed frame. More...
 
bool transformHasProblems (const std::string &frame, ros::Time time, std::string &error)
 Check to see if a transform is known between a given frame and the fixed frame. More...
 
void update ()
 Clear the internal cache. More...
 
 ~FrameManager () override
 Destructor. More...
 

Private Types

typedef std::map< CacheKey, CacheEntryM_Cache
 

Private Member Functions

bool adjustTime (const std::string &frame, ros::Time &time)
 
template<class M , class TfFilterFailureReasonType >
void failureCallback (const ros::MessageEvent< M const > &msg_evt, TfFilterFailureReasonType reason, Display *display)
 
void messageArrived (const std::string &frame_id, const ros::Time &stamp, const std::string &caller_id, Display *display)
 
template<class M >
void messageCallback (const ros::MessageEvent< M const > &msg_evt, Display *display)
 
template<class TfFilterFailureReasonType >
void messageFailed (const std::string &frame_id, const ros::Time &stamp, const std::string &caller_id, TfFilterFailureReasonType reason, Display *display)
 
void messageFailedImpl (const std::string &caller_id, const std::string &status_text, Display *display)
 

Private Attributes

M_Cache cache_
 
boost::mutex cache_mutex_
 
double current_delta_
 
std::string fixed_frame_
 
bool pause_
 
double sync_delta_
 
SyncMode sync_mode_
 
ros::Time sync_time_
 
boost::shared_ptr< tf::TransformListenertf_
 

Detailed Description

Helper class for transforming data into Ogre's world frame (the fixed frame).

During one frame update (nominally 33ms), the tf tree stays consistent and queries are cached for speedup.

Definition at line 70 of file frame_manager.h.

Member Typedef Documentation

◆ M_Cache

typedef std::map<CacheKey, CacheEntry> rviz::FrameManager::M_Cache
private

Definition at line 376 of file frame_manager.h.

Member Enumeration Documentation

◆ SyncMode

Enumerator
SyncOff 
SyncExact 
SyncApprox 

Definition at line 74 of file frame_manager.h.

Constructor & Destructor Documentation

◆ FrameManager() [1/2]

rviz::FrameManager::FrameManager ( )

Default constructor, which will create a tf::TransformListener automatically.

Definition at line 47 of file frame_manager.cpp.

◆ FrameManager() [2/2]

rviz::FrameManager::FrameManager ( boost::shared_ptr< tf::TransformListener tf)
explicitoptional

Constructor.

Parameters
tfa pointer to tf::TransformListener (should not be used anywhere else because of thread safety)

Definition at line 55 of file frame_manager.cpp.

◆ ~FrameManager()

rviz::FrameManager::~FrameManager ( )
overrideoptional

Destructor.

FrameManager should not need to be destroyed by hand, just destroy the boost::shared_ptr returned by instance(), and it will be deleted when the last reference is removed.

Definition at line 66 of file frame_manager.cpp.

Member Function Documentation

◆ adjustTime()

bool rviz::FrameManager::adjustTime ( const std::string &  frame,
ros::Time time 
)
optionalprivate

Definition at line 163 of file frame_manager.cpp.

◆ discoverFailureReason() [1/2]

std::string rviz::FrameManager::discoverFailureReason ( const std::string &  frame_id,
const ros::Time stamp,
const std::string &  caller_id,
tf::FilterFailureReason  reason 
)
optional

Create a description of a transform problem.

Parameters
frame_idThe name of the frame with issues.
stampThe time for which the problem was detected.
caller_idDummy parameter, not used.
reasonThe reason given by the tf::MessageFilter in its failure callback.
Returns
An error message describing the problem.

Once a problem has been detected with a given frame or transform, call this to get an error message describing the problem.

Definition at line 352 of file frame_manager.cpp.

◆ discoverFailureReason() [2/2]

std::string rviz::FrameManager::discoverFailureReason ( const std::string &  frame_id,
const ros::Time stamp,
const std::string &  caller_id,
tf2_ros::FilterFailureReason  reason 
)
optional

Create a description of a transform problem.

Parameters
frame_idThe name of the frame with issues.
stampThe time for which the problem was detected.
caller_idDummy parameter, not used.
reasonThe reason given by the tf2_ros::MessageFilter in its failure callback.
Returns
An error message describing the problem.

Once a problem has been detected with a given frame or transform, call this to get an error message describing the problem.

Definition at line 375 of file frame_manager.cpp.

◆ failureCallback()

template<class M , class TfFilterFailureReasonType >
void rviz::FrameManager::failureCallback ( const ros::MessageEvent< M const > &  msg_evt,
TfFilterFailureReasonType  reason,
Display display 
)
inlineoptionalprivate

Definition at line 308 of file frame_manager.h.

◆ fixedFrameChanged

void rviz::FrameManager::fixedFrameChanged ( )
optionalsignal

Emitted whenever the fixed frame changes.

◆ frameHasProblems()

bool rviz::FrameManager::frameHasProblems ( const std::string &  frame,
ros::Time  time,
std::string &  error 
)
optional

Check to see if a frame exists in the tf::TransformListener.

Parameters
[in]frameThe name of the frame to check.
[in]timeDummy parameter, not actually used.
[out]errorIf the frame does not exist, an error message is stored here.
Returns
true if the frame does not exist, false if it does exist.

Definition at line 295 of file frame_manager.cpp.

◆ getFixedFrame()

const std::string& rviz::FrameManager::getFixedFrame ( )
inlineoptional

Return the current fixed frame name.

Definition at line 238 of file frame_manager.h.

◆ getPause()

bool rviz::FrameManager::getPause ( )
inlineoptional

Definition at line 114 of file frame_manager.h.

◆ getSyncMode()

SyncMode rviz::FrameManager::getSyncMode ( )
inlineoptional

Definition at line 122 of file frame_manager.h.

◆ getTF2BufferPtr()

const std::shared_ptr<tf2_ros::Buffer> rviz::FrameManager::getTF2BufferPtr ( )
inlineoptional

Definition at line 257 of file frame_manager.h.

◆ getTFClient()

tf::TransformListener* rviz::FrameManager::getTFClient ( )
inlineoptional

Return the tf::TransformListener used to receive transform data.

Definition at line 244 of file frame_manager.h.

◆ getTFClientPtr()

const boost::shared_ptr<tf::TransformListener>& rviz::FrameManager::getTFClientPtr ( )
inlineoptional

Return a boost shared pointer to the tf::TransformListener used to receive transform data.

Definition at line 252 of file frame_manager.h.

◆ getTime()

ros::Time rviz::FrameManager::getTime ( )
inlineoptional

Get current time, depending on the sync mode.

Definition at line 131 of file frame_manager.h.

◆ getTransform() [1/2]

template<typename Header >
bool rviz::FrameManager::getTransform ( const Header header,
Ogre::Vector3 &  position,
Ogre::Quaternion &  orientation 
)
inlineoptional

Return the pose for a header, relative to the fixed frame, in Ogre classes.

Parameters
[in]headerThe source of the frame name and time.
[out]positionThe position of the header frame relative to the fixed frame.
[out]orientationThe orientation of the header frame relative to the fixed frame.
Returns
true on success, false on failure.

Definition at line 142 of file frame_manager.h.

◆ getTransform() [2/2]

bool rviz::FrameManager::getTransform ( const std::string &  frame,
ros::Time  time,
Ogre::Vector3 &  position,
Ogre::Quaternion &  orientation 
)
optional

Return the pose for a frame relative to the fixed frame, in Ogre classes, at a given time.

Parameters
[in]frameThe frame to find the pose of.
[in]timeThe time at which to get the pose.
[out]positionThe position of the frame relative to the fixed frame.
[out]orientationThe orientation of the frame relative to the fixed frame.
Returns
true on success, false on failure.

Definition at line 204 of file frame_manager.cpp.

◆ messageArrived()

void rviz::FrameManager::messageArrived ( const std::string &  frame_id,
const ros::Time stamp,
const std::string &  caller_id,
Display display 
)
optionalprivate

Definition at line 398 of file frame_manager.cpp.

◆ messageCallback()

template<class M >
void rviz::FrameManager::messageCallback ( const ros::MessageEvent< M const > &  msg_evt,
Display display 
)
inlineoptionalprivate

Definition at line 299 of file frame_manager.h.

◆ messageFailed()

template<class TfFilterFailureReasonType >
void rviz::FrameManager::messageFailed ( const std::string &  frame_id,
const ros::Time stamp,
const std::string &  caller_id,
TfFilterFailureReasonType  reason,
Display display 
)
inlineoptionalprivate

Definition at line 326 of file frame_manager.h.

◆ messageFailedImpl()

void rviz::FrameManager::messageFailedImpl ( const std::string &  caller_id,
const std::string &  status_text,
Display display 
)
optionalprivate

Definition at line 406 of file frame_manager.cpp.

◆ registerFilterForTransformStatusCheck() [1/2]

template<class M >
void rviz::FrameManager::registerFilterForTransformStatusCheck ( tf::MessageFilter< M > *  filter,
Display display 
)
inlineoptional

Connect a tf::MessageFilter's callbacks to success and failure handler functions in this FrameManager.

Parameters
filterThe tf::MessageFilter to connect to.
displayThe Display using the filter.

FrameManager has internal functions for handling success and failure of tf::MessageFilters which call Display::setStatus() based on success or failure of the filter, including appropriate error messages.

Definition at line 214 of file frame_manager.h.

◆ registerFilterForTransformStatusCheck() [2/2]

template<class M >
void rviz::FrameManager::registerFilterForTransformStatusCheck ( tf2_ros::MessageFilter< M > *  filter,
Display display 
)
inlineoptional

Connect success and failure callbacks to a tf2_ros::MessageFilter.

Parameters
filterThe tf2_ros::MessageFilter to connect to.
displayThe Display using the filter.

FrameManager has internal functions for handling success and failure of tf2_ros::MessageFilters which call Display::setStatus() based on success or failure of the filter, including appropriate error messages.

Definition at line 230 of file frame_manager.h.

◆ setFixedFrame()

void rviz::FrameManager::setFixedFrame ( const std::string &  frame)
optional

Set the frame to consider "fixed", into which incoming data is transformed.

The fixed frame serves as the reference for all getTransform() and transform() functions in FrameManager.

Definition at line 103 of file frame_manager.cpp.

◆ setPause()

void rviz::FrameManager::setPause ( bool  pause)
optional

Enable/disable pause mode.

Definition at line 122 of file frame_manager.cpp.

◆ setSyncMode()

void rviz::FrameManager::setSyncMode ( SyncMode  mode)
optional

Set synchronization mode (off/exact/approximate)

Definition at line 127 of file frame_manager.cpp.

◆ syncTime()

void rviz::FrameManager::syncTime ( ros::Time  time)
optional

Synchronize with given time.

Definition at line 135 of file frame_manager.cpp.

◆ transform() [1/2]

template<typename Header >
bool rviz::FrameManager::transform ( const Header header,
const geometry_msgs::Pose pose,
Ogre::Vector3 &  position,
Ogre::Quaternion &  orientation 
)
inlineoptional

Transform a pose from a frame into the fixed frame.

Parameters
[in]headerThe source of the input frame and time.
[in]poseThe input pose, relative to the header frame.
[out]positionPosition part of pose relative to the fixed frame.
[out]orientationOrientation part of pose relative to the fixed frame.
Returns
true on success, false on failure.

Definition at line 165 of file frame_manager.h.

◆ transform() [2/2]

bool rviz::FrameManager::transform ( const std::string &  frame,
ros::Time  time,
const geometry_msgs::Pose pose,
Ogre::Vector3 &  position,
Ogre::Quaternion &  orientation 
)
optional

Transform a pose from a frame into the fixed frame.

Parameters
[in]frameThe input frame.
[in]timeThe time at which to get the pose.
[in]poseThe input pose, relative to the input frame.
[out]positionPosition part of pose relative to the fixed frame.
[out]orientationOrientation part of pose relative to the fixed frame.
Returns
true on success, false on failure.

Definition at line 245 of file frame_manager.cpp.

◆ transformHasProblems()

bool rviz::FrameManager::transformHasProblems ( const std::string &  frame,
ros::Time  time,
std::string &  error 
)
optional

Check to see if a transform is known between a given frame and the fixed frame.

Parameters
[in]frameThe name of the frame to check.
[in]timeThe time at which the transform is desired.
[out]errorIf the transform is not known, an error message is stored here.
Returns
true if the transform is not known, false if it is.

Definition at line 310 of file frame_manager.cpp.

◆ update()

void rviz::FrameManager::update ( )
optional

Clear the internal cache.

Definition at line 70 of file frame_manager.cpp.

Member Data Documentation

◆ cache_

M_Cache rviz::FrameManager::cache_
private

Definition at line 379 of file frame_manager.h.

◆ cache_mutex_

boost::mutex rviz::FrameManager::cache_mutex_
private

Definition at line 378 of file frame_manager.h.

◆ current_delta_

double rviz::FrameManager::current_delta_
private

Definition at line 393 of file frame_manager.h.

◆ fixed_frame_

std::string rviz::FrameManager::fixed_frame_
private

Definition at line 382 of file frame_manager.h.

◆ pause_

bool rviz::FrameManager::pause_
private

Definition at line 384 of file frame_manager.h.

◆ sync_delta_

double rviz::FrameManager::sync_delta_
private

Definition at line 392 of file frame_manager.h.

◆ sync_mode_

SyncMode rviz::FrameManager::sync_mode_
private

Definition at line 386 of file frame_manager.h.

◆ sync_time_

ros::Time rviz::FrameManager::sync_time_
private

Definition at line 389 of file frame_manager.h.

◆ tf_

boost::shared_ptr<tf::TransformListener> rviz::FrameManager::tf_
private

Definition at line 381 of file frame_manager.h.


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


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Sat May 27 2023 02:06:25