$search

rviz::FrameManager Class Reference

#include <frame_manager.h>

List of all members.

Classes

struct  CacheEntry
struct  CacheKey

Public Member Functions

 __attribute__ ((deprecated)) bool transform(const std
template<typename Header >
 __attribute__ ((deprecated)) bool getTransform(const Header &header
std::string discoverFailureReason (const std::string &frame_id, const ros::Time &stamp, const std::string &caller_id, tf::FilterFailureReason reason)
bool frameHasProblems (const std::string &frame, ros::Time time, std::string &error)
 FrameManager ()
const std::string & getFixedFrame ()
tf::TransformListenergetTFClient ()
bool getTransform (const std::string &frame, ros::Time time, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
template<typename Header >
bool getTransform (const Header &header, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
Ogre::Vector3 Ogre::Quaternion
bool relative return 
getTransform (header, position, orientation)
template<class M >
void registerFilterForTransformStatusCheck (tf::MessageFilter< M > &filter, Display *display)
void setFixedFrame (const std::string &frame)
bool transform (const std::string &frame, ros::Time time, const geometry_msgs::Pose &pose, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
template<typename Header >
bool transform (const Header &header, const geometry_msgs::Pose &pose, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
bool transformHasProblems (const std::string &frame, ros::Time time, std::string &error)
void update ()
 ~FrameManager ()

Static Public Member Functions

static FrameManagerPtr instance ()

Public Attributes

Ogre::Vector3 Ogre::Quaternion & orientation
Ogre::Vector3 & position

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)
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

Definition at line 70 of file frame_manager.h.


Member Typedef Documentation

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

Definition at line 187 of file frame_manager.h.


Constructor & Destructor Documentation

rviz::FrameManager::FrameManager (  ) 

Definition at line 47 of file frame_manager.cpp.

rviz::FrameManager::~FrameManager (  ) 

Definition at line 52 of file frame_manager.cpp.


Member Function Documentation

rviz::FrameManager::__attribute__ ( (deprecated)   )  const [inline]

Definition at line 109 of file frame_manager.h.

template<typename Header >
rviz::FrameManager::__attribute__ ( (deprecated)   )  const [inline]
std::string rviz::FrameManager::discoverFailureReason ( const std::string &  frame_id,
const ros::Time stamp,
const std::string &  caller_id,
tf::FilterFailureReason  reason 
)

Definition at line 192 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 148 of file frame_manager.h.

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

Definition at line 140 of file frame_manager.cpp.

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

Definition at line 135 of file frame_manager.h.

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

Definition at line 136 of file frame_manager.h.

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

Definition at line 70 of file frame_manager.cpp.

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

Definition at line 90 of file frame_manager.h.

Ogre::Vector3 Ogre::Quaternion bool relative return rviz::FrameManager::getTransform ( header  ,
position  ,
orientation   
)
Type Constraints
FrameManagerPtr rviz::FrameManager::instance (  )  [static]

Definition at line 33 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 212 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 142 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 217 of file frame_manager.cpp.

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

Definition at line 129 of file frame_manager.h.

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

Definition at line 63 of file frame_manager.cpp.

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

Definition at line 103 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]

Definition at line 103 of file frame_manager.h.

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

Definition at line 155 of file frame_manager.cpp.

void rviz::FrameManager::update (  ) 

Definition at line 57 of file frame_manager.cpp.


Member Data Documentation

Definition at line 190 of file frame_manager.h.

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

Definition at line 189 of file frame_manager.h.

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

Definition at line 193 of file frame_manager.h.

Ogre::Vector3 Ogre::Quaternion& rviz::FrameManager::orientation

Definition at line 83 of file frame_manager.h.

Definition at line 83 of file frame_manager.h.

Definition at line 192 of file frame_manager.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Defines


rviz
Author(s): Josh Faust, Dave Hershberger
autogenerated on Sat Mar 2 14:17:35 2013