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...
 
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 (boost::shared_ptr< tf::TransformListener > tf=boost::shared_ptr< tf::TransformListener >())
 Constructor. More...
 
const std::string & getFixedFrame ()
 Return the current fixed frame name. More...
 
bool getPause ()
 
SyncMode getSyncMode ()
 
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...
 
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 ()
 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 >
void failureCallback (const ros::MessageEvent< M const > &msg_evt, tf::FilterFailureReason 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)
 
void messageFailed (const std::string &frame_id, const ros::Time &stamp, const std::string &caller_id, tf::FilterFailureReason reason, 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 63 of file frame_manager.h.

Member Typedef Documentation

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

Definition at line 263 of file frame_manager.h.

Member Enumeration Documentation

Enumerator
SyncOff 
SyncExact 
SyncApprox 

Definition at line 68 of file frame_manager.h.

Constructor & Destructor Documentation

rviz::FrameManager::FrameManager ( boost::shared_ptr< tf::TransformListener tf = boost::shared_ptr<tf::TransformListener>())

Constructor.

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

Definition at line 42 of file frame_manager.cpp.

rviz::FrameManager::~FrameManager ( )

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 51 of file frame_manager.cpp.

Member Function Documentation

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

Definition at line 148 of file frame_manager.cpp.

std::string rviz::FrameManager::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.

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 326 of file frame_manager.cpp.

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

Definition at line 221 of file frame_manager.h.

void rviz::FrameManager::fixedFrameChanged ( )
signal

Emitted whenever the fixed frame changes.

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

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 269 of file frame_manager.cpp.

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

Return the current fixed frame name.

Definition at line 181 of file frame_manager.h.

bool rviz::FrameManager::getPause ( )
inline

Definition at line 95 of file frame_manager.h.

SyncMode rviz::FrameManager::getSyncMode ( )
inline

Definition at line 100 of file frame_manager.h.

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

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

Definition at line 184 of file frame_manager.h.

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

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

Definition at line 187 of file frame_manager.h.

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

Get current time, depending on the sync mode.

Definition at line 106 of file frame_manager.h.

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

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 114 of file frame_manager.h.

bool rviz::FrameManager::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.

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 189 of file frame_manager.cpp.

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

Definition at line 346 of file frame_manager.cpp.

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

Definition at line 212 of file frame_manager.h.

void rviz::FrameManager::messageFailed ( const std::string &  frame_id,
const ros::Time stamp,
const std::string &  caller_id,
tf::FilterFailureReason  reason,
Display display 
)
private

Definition at line 352 of file frame_manager.cpp.

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

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 174 of file frame_manager.h.

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

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 88 of file frame_manager.cpp.

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

Enable/disable pause mode.

Definition at line 107 of file frame_manager.cpp.

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

Set synchronization mode (off/exact/approximate)

Definition at line 112 of file frame_manager.cpp.

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

Synchronize with given time.

Definition at line 120 of file frame_manager.cpp.

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

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 134 of file frame_manager.h.

bool rviz::FrameManager::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.

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 227 of file frame_manager.cpp.

bool rviz::FrameManager::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.

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 284 of file frame_manager.cpp.

void rviz::FrameManager::update ( )

Clear the internal cache.

Definition at line 55 of file frame_manager.cpp.

Member Data Documentation

M_Cache rviz::FrameManager::cache_
private

Definition at line 266 of file frame_manager.h.

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

Definition at line 265 of file frame_manager.h.

double rviz::FrameManager::current_delta_
private

Definition at line 280 of file frame_manager.h.

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

Definition at line 269 of file frame_manager.h.

bool rviz::FrameManager::pause_
private

Definition at line 271 of file frame_manager.h.

double rviz::FrameManager::sync_delta_
private

Definition at line 279 of file frame_manager.h.

SyncMode rviz::FrameManager::sync_mode_
private

Definition at line 273 of file frame_manager.h.

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

Definition at line 276 of file frame_manager.h.

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

Definition at line 268 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 Apr 27 2019 02:33:43