Helper class for transforming data into Ogre's world frame (the fixed frame). More...
#include <frame_manager.h>
Classes | |
struct | CacheEntry |
struct | CacheKey |
Signals | |
void | fixedFrameChanged () |
Emitted whenever the fixed frame changes. | |
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. | |
FrameManager () | |
const std::string & | getFixedFrame () |
Return the current fixed frame name. | |
tf::TransformListener * | getTFClient () |
Return the tf::TransformListener used to receive transform data. | |
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<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. | |
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. | |
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. | |
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 | 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. | |
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_ |
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 61 of file frame_manager.h.
typedef std::map<CacheKey, CacheEntry > rviz::FrameManager::M_Cache [private] |
Definition at line 223 of file frame_manager.h.
rviz::FrameManager::FrameManager | ( | ) |
Definition at line 40 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 45 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.
frame_id | The name of the frame with issues. | |
stamp | The time for which the problem was detected. | |
caller_id | Dummy parameter, not used. | |
reason | The reason given by the tf::MessageFilter in its failure callback. |
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 197 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 184 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.
[in] | frame | The name of the frame to check. |
[in] | time | Dummy parameter, not actually used. |
[out] | error | If the frame does not exist, an error message is stored here. |
Definition at line 145 of file frame_manager.cpp.
const std::string& rviz::FrameManager::getFixedFrame | ( | ) | [inline] |
Return the current fixed frame name.
Definition at line 153 of file frame_manager.h.
tf::TransformListener* rviz::FrameManager::getTFClient | ( | ) | [inline] |
Return the tf::TransformListener used to receive transform data.
Definition at line 156 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.
[in] | frame | The frame to find the pose of. |
[in] | time | The time at which to get the pose. |
[out] | position | The position of the frame relative to the fixed frame. |
[out] | orientation | The orientation of the frame relative to the fixed frame. |
Definition at line 75 of file frame_manager.cpp.
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.
[in] | header | The source of the frame name and time. |
[out] | position | The position of the header frame relative to the fixed frame. |
[out] | orientation | The orientation of the header frame relative to the fixed frame. |
Definition at line 86 of file frame_manager.h.
void rviz::FrameManager::messageArrived | ( | const std::string & | frame_id, | |
const ros::Time & | stamp, | |||
const std::string & | caller_id, | |||
Display * | display | |||
) | [private] |
Definition at line 217 of file frame_manager.cpp.
void rviz::FrameManager::messageCallback | ( | const boost::shared_ptr< M const > & | msg, | |
Display * | display | |||
) | [inline, private] |
Definition at line 178 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 223 of file frame_manager.cpp.
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.
filter | The tf::MessageFilter to connect to. | |
display | The 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 146 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 56 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 | |||
) |
Transform a pose from a frame into the fixed frame.
[in] | frame | The input frame. |
[in] | time | The time at which to get the pose. |
[in] | pose | The input pose, relative to the input frame. |
[out] | position | Position part of pose relative to the fixed frame. |
[out] | orientation,: | Orientation part of pose relative to the fixed frame. |
Definition at line 108 of file frame_manager.cpp.
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.
[in] | header | The source of the input frame and time. |
[in] | pose | The input pose, relative to the header frame. |
[out] | position | Position part of pose relative to the fixed frame. |
[out] | orientation,: | Orientation part of pose relative to the fixed frame. |
Definition at line 106 of file frame_manager.h.
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.
[in] | frame | The name of the frame to check. |
[in] | time | The time at which the transform is desired. |
[out] | error | If the transform is not known, an error message is stored here. |
Definition at line 160 of file frame_manager.cpp.
void rviz::FrameManager::update | ( | ) |
Clear the internal cache.
Definition at line 50 of file frame_manager.cpp.
M_Cache rviz::FrameManager::cache_ [private] |
Definition at line 226 of file frame_manager.h.
boost::mutex rviz::FrameManager::cache_mutex_ [private] |
Definition at line 225 of file frame_manager.h.
std::string rviz::FrameManager::fixed_frame_ [private] |
Definition at line 229 of file frame_manager.h.
tf::TransformListener* rviz::FrameManager::tf_ [private] |
Definition at line 228 of file frame_manager.h.