#include <frame_manager.h>
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) |
bool | frameHasProblems (const std::string &frame, ros::Time time, std::string &error) |
FrameManager () | |
const std::string & | getFixedFrame () |
tf::TransformListener * | getTFClient () |
bool | getTransform (const std::string &frame, ros::Time time, Ogre::Vector3 &position, Ogre::Quaternion &orientation, bool relative_orientation) |
template<typename Header > | |
bool | getTransform (const Header &header, Ogre::Vector3 &position, Ogre::Quaternion &orientation, bool relative_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, bool relative_orientation) |
template<typename Header > | |
bool | transform (const Header &header, const geometry_msgs::Pose &pose, Ogre::Vector3 &position, Ogre::Quaternion &orientation, bool relative_orientation) |
bool | transformHasProblems (const std::string &frame, ros::Time time, std::string &error) |
void | update () |
~FrameManager () | |
Static Public Member Functions | |
static FrameManagerPtr | instance () |
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::TransformListener * | tf_ |
Definition at line 59 of file frame_manager.h.
typedef std::map<CacheKey, CacheEntry > rviz::FrameManager::M_Cache [private] |
Definition at line 154 of file frame_manager.h.
rviz::FrameManager::FrameManager | ( | ) |
Definition at line 55 of file frame_manager.cpp.
rviz::FrameManager::~FrameManager | ( | ) |
Definition at line 60 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 | |||
) |
Definition at line 205 of file frame_manager.cpp.
void rviz::FrameManager::failureCallback | ( | const boost::shared_ptr< M const > & | msg, | |
tf::FilterFailureReason | reason, | |||
Display * | display | |||
) | [inline, private] |
Definition at line 109 of file frame_manager.h.
bool rviz::FrameManager::frameHasProblems | ( | const std::string & | frame, | |
ros::Time | time, | |||
std::string & | error | |||
) |
Definition at line 153 of file frame_manager.cpp.
const std::string& rviz::FrameManager::getFixedFrame | ( | ) | [inline] |
Definition at line 96 of file frame_manager.h.
tf::TransformListener* rviz::FrameManager::getTFClient | ( | ) | [inline] |
Definition at line 97 of file frame_manager.h.
bool rviz::FrameManager::getTransform | ( | const std::string & | frame, | |
ros::Time | time, | |||
Ogre::Vector3 & | position, | |||
Ogre::Quaternion & | orientation, | |||
bool | relative_orientation | |||
) |
Definition at line 78 of file frame_manager.cpp.
bool rviz::FrameManager::getTransform | ( | const Header & | header, | |
Ogre::Vector3 & | position, | |||
Ogre::Quaternion & | orientation, | |||
bool | relative_orientation | |||
) | [inline] |
Definition at line 70 of file frame_manager.h.
FrameManagerPtr rviz::FrameManager::instance | ( | ) | [static] |
Definition at line 41 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 225 of file frame_manager.cpp.
void rviz::FrameManager::messageCallback | ( | const boost::shared_ptr< M const > & | msg, | |
Display * | display | |||
) | [inline, private] |
Definition at line 103 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 230 of file frame_manager.cpp.
void rviz::FrameManager::registerFilterForTransformStatusCheck | ( | tf::MessageFilter< M > & | filter, | |
Display * | display | |||
) | [inline] |
Definition at line 90 of file frame_manager.h.
void rviz::FrameManager::setFixedFrame | ( | const std::string & | frame | ) |
Definition at line 71 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, | |||
bool | relative_orientation | |||
) |
Definition at line 111 of file frame_manager.cpp.
bool rviz::FrameManager::transform | ( | const Header & | header, | |
const geometry_msgs::Pose & | pose, | |||
Ogre::Vector3 & | position, | |||
Ogre::Quaternion & | orientation, | |||
bool | relative_orientation | |||
) | [inline] |
Definition at line 78 of file frame_manager.h.
bool rviz::FrameManager::transformHasProblems | ( | const std::string & | frame, | |
ros::Time | time, | |||
std::string & | error | |||
) |
Definition at line 168 of file frame_manager.cpp.
void rviz::FrameManager::update | ( | ) |
Definition at line 65 of file frame_manager.cpp.
M_Cache rviz::FrameManager::cache_ [private] |
Definition at line 157 of file frame_manager.h.
boost::mutex rviz::FrameManager::cache_mutex_ [private] |
Definition at line 156 of file frame_manager.h.
std::string rviz::FrameManager::fixed_frame_ [private] |
Definition at line 160 of file frame_manager.h.
tf::TransformListener* rviz::FrameManager::tf_ [private] |
Definition at line 159 of file frame_manager.h.