Helper class for transforming data into Ogre's world frame (the fixed frame). More...
#include <frame_manager.h>
Classes | |
struct | CacheEntry |
struct | CacheKey |
Public Types | |
enum | SyncMode { SyncOff = 0, SyncExact, SyncApprox } |
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 (boost::shared_ptr< tf::TransformListener > tf=boost::shared_ptr< tf::TransformListener >()) | |
Constructor. | |
const std::string & | getFixedFrame () |
Return the current fixed frame name. | |
bool | getPause () |
SyncMode | getSyncMode () |
tf::TransformListener * | getTFClient () |
Return the tf::TransformListener used to receive transform data. | |
const boost::shared_ptr < tf::TransformListener > & | getTFClientPtr () |
Return a boost shared pointer to the tf::TransformListener used to receive transform data. | |
ros::Time | getTime () |
Get current time, depending on the sync mode. | |
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. | |
void | setPause (bool pause) |
Enable/disable pause mode. | |
void | setSyncMode (SyncMode mode) |
Set synchronization mode (off/exact/approximate) | |
void | syncTime (ros::Time time) |
Synchronize with given time. | |
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. | |
Private Types | |
typedef std::map< CacheKey, CacheEntry > | M_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::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 63 of file frame_manager.h.
typedef std::map<CacheKey, CacheEntry > rviz::FrameManager::M_Cache [private] |
Definition at line 263 of file frame_manager.h.
Definition at line 68 of file frame_manager.h.
rviz::FrameManager::FrameManager | ( | boost::shared_ptr< tf::TransformListener > | tf = boost::shared_ptr<tf::TransformListener>() | ) |
Constructor.
tf | a pointer to tf::TransformListener (should not be used anywhere else because of thread safety) |
Definition at line 42 of file frame_manager.cpp.
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.
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.
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 326 of file frame_manager.cpp.
void rviz::FrameManager::failureCallback | ( | const ros::MessageEvent< M const > & | msg_evt, |
tf::FilterFailureReason | reason, | ||
Display * | display | ||
) | [inline, private] |
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.
[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 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.
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 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.
[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 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.
void rviz::FrameManager::messageCallback | ( | const ros::MessageEvent< M const > & | msg_evt, |
Display * | display | ||
) | [inline, private] |
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.
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 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.
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 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.
[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 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.
[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 284 of file frame_manager.cpp.
void rviz::FrameManager::update | ( | ) |
Clear the internal cache.
Definition at line 55 of file frame_manager.cpp.
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.