Classes | Public Member Functions | Static Public Member Functions | Private Types | Private Member Functions | Private Attributes
rviz::FrameManager Class Reference

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

#include <frame_manager.h>

List of all members.

Classes

struct  CacheEntry
struct  CacheKey

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.
bool frameHasProblems (const std::string &frame, ros::Time time, std::string &error)
 Check to see if a frame exists in the tf::TransformListener.
const std::string & getFixedFrame ()
 Return the current fixed frame name.
tf::TransformListenergetTFClient ()
 Return the tf::TransformListener used to receive transform data.
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.
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.
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.
void setFixedFrame (const std::string &frame)
 Set the frame to consider "fixed", into which incoming data is transformed.
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.
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.
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.
void update ()
 Clear the internal cache.
 ~FrameManager ()
 Destructor.

Static Public Member Functions

static FrameManagerPtr instance ()
 Return a shared pointer to a single instance of FrameManager.

Private Types

typedef std::map< CacheKey,
CacheEntry
M_Cache

Private Member Functions

template<class M >
void failureCallback (const boost::shared_ptr< M const > &msg, tf::FilterFailureReason reason, Display *display)
 FrameManager ()
void messageArrived (const std::string &frame_id, const ros::Time &stamp, const std::string &caller_id, Display *display)
template<class M >
void messageCallback (const boost::shared_ptr< M const > &msg, 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_
std::string fixed_frame_
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 227 of file frame_manager.h.


Constructor & Destructor Documentation

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

Definition at line 54 of file frame_manager.cpp.


Member Function Documentation

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

template<class M >
void rviz::FrameManager::failureCallback ( const boost::shared_ptr< M const > &  msg,
tf::FilterFailureReason  reason,
Display display 
) [inline, private]

Definition at line 188 of file frame_manager.h.

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

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

Return the current fixed frame name.

Definition at line 159 of file frame_manager.h.

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

Definition at line 162 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 92 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 77 of file frame_manager.cpp.

Return a shared pointer to a single instance of FrameManager.

FrameManager is a singleton which only exists as long as shared pointers from instance() are held, because only a weak pointer is kept internally.

Definition at line 40 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 219 of file frame_manager.cpp.

template<class M >
void rviz::FrameManager::messageCallback ( const boost::shared_ptr< M const > &  msg,
Display display 
) [inline, private]

Definition at line 182 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 224 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 152 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 70 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]orientation,:Orientation part of pose relative to the fixed frame.
Returns:
true on success, false on failure.

Definition at line 112 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]orientation,:Orientation part of pose relative to the fixed frame.
Returns:
true on success, false on failure.

Definition at line 110 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 162 of file frame_manager.cpp.

Clear the internal cache.

Definition at line 64 of file frame_manager.cpp.


Member Data Documentation

Definition at line 230 of file frame_manager.h.

boost::mutex rviz::FrameManager::cache_mutex_ [private]

Definition at line 229 of file frame_manager.h.

std::string rviz::FrameManager::fixed_frame_ [private]

Definition at line 233 of file frame_manager.h.

Definition at line 232 of file frame_manager.h.


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


rviz
Author(s): Dave Hershberger, Josh Faust
autogenerated on Mon Jan 6 2014 11:54:33