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. More... | |
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. More... | |
std::string | discoverFailureReason (const std::string &frame_id, const ros::Time &stamp, const std::string &caller_id, tf2_ros::FilterFailureReason reason) |
bool | frameHasProblems (const std::string &frame, ros::Time time, std::string &error) |
Check to see if a frame exists in the tf::TransformListener. More... | |
FrameManager () | |
Default constructor, which will create a tf::TransformListener automatically. More... | |
FrameManager (boost::shared_ptr< tf::TransformListener > tf) | |
Constructor. More... | |
const std::string & | getFixedFrame () |
Return the current fixed frame name. More... | |
bool | getPause () |
SyncMode | getSyncMode () |
const std::shared_ptr< tf2_ros::Buffer > | getTF2BufferPtr () |
tf::TransformListener * | getTFClient () |
Return the tf::TransformListener used to receive transform data. More... | |
const boost::shared_ptr< tf::TransformListener > & | getTFClientPtr () |
Return a boost shared pointer to the tf::TransformListener used to receive transform data. More... | |
ros::Time | getTime () |
Get current time, depending on the sync mode. More... | |
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. More... | |
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. More... | |
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. More... | |
template<class M > | |
void | registerFilterForTransformStatusCheck (tf2_ros::MessageFilter< M > *filter, Display *display) |
void | setFixedFrame (const std::string &frame) |
Set the frame to consider "fixed", into which incoming data is transformed. More... | |
void | setPause (bool pause) |
Enable/disable pause mode. More... | |
void | setSyncMode (SyncMode mode) |
Set synchronization mode (off/exact/approximate) More... | |
void | syncTime (ros::Time time) |
Synchronize with given time. More... | |
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. More... | |
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. More... | |
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. More... | |
void | update () |
Clear the internal cache. More... | |
~FrameManager () override | |
Destructor. More... | |
Private Types | |
typedef std::map< CacheKey, CacheEntry > | M_Cache |
Private Member Functions | |
bool | adjustTime (const std::string &frame, ros::Time &time) |
template<class M , class TfFilterFailureReasonType > | |
void | failureCallback (const ros::MessageEvent< M const > &msg_evt, TfFilterFailureReasonType 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) |
template<class TfFilterFailureReasonType > | |
void | messageFailed (const std::string &frame_id, const ros::Time &stamp, const std::string &caller_id, TfFilterFailureReasonType reason, Display *display) |
void | messageFailedImpl (const std::string &caller_id, const std::string &status_text, 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 70 of file frame_manager.h.
|
private |
Definition at line 376 of file frame_manager.h.
Enumerator | |
---|---|
SyncOff | |
SyncExact | |
SyncApprox |
Definition at line 74 of file frame_manager.h.
rviz::FrameManager::FrameManager | ( | ) |
Default constructor, which will create a tf::TransformListener automatically.
Definition at line 47 of file frame_manager.cpp.
|
explicitoptional |
Constructor.
tf | a pointer to tf::TransformListener (should not be used anywhere else because of thread safety) |
Definition at line 55 of file frame_manager.cpp.
|
overrideoptional |
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 66 of file frame_manager.cpp.
|
optionalprivate |
Definition at line 163 of file frame_manager.cpp.
|
optional |
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 352 of file frame_manager.cpp.
|
optional |
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 tf2_ros::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 375 of file frame_manager.cpp.
|
inlineoptionalprivate |
Definition at line 308 of file frame_manager.h.
|
optionalsignal |
Emitted whenever the fixed frame changes.
|
optional |
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 295 of file frame_manager.cpp.
|
inlineoptional |
Return the current fixed frame name.
Definition at line 238 of file frame_manager.h.
|
inlineoptional |
Definition at line 114 of file frame_manager.h.
|
inlineoptional |
Definition at line 122 of file frame_manager.h.
|
inlineoptional |
Definition at line 257 of file frame_manager.h.
|
inlineoptional |
Return the tf::TransformListener used to receive transform data.
Definition at line 244 of file frame_manager.h.
|
inlineoptional |
Return a boost shared pointer to the tf::TransformListener used to receive transform data.
Definition at line 252 of file frame_manager.h.
|
inlineoptional |
Get current time, depending on the sync mode.
Definition at line 131 of file frame_manager.h.
|
inlineoptional |
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 142 of file frame_manager.h.
|
optional |
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 204 of file frame_manager.cpp.
|
optionalprivate |
Definition at line 398 of file frame_manager.cpp.
|
inlineoptionalprivate |
Definition at line 299 of file frame_manager.h.
|
inlineoptionalprivate |
Definition at line 326 of file frame_manager.h.
|
optionalprivate |
Definition at line 406 of file frame_manager.cpp.
|
inlineoptional |
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 214 of file frame_manager.h.
|
inlineoptional |
Connect success and failure callbacks to a tf2_ros::MessageFilter.
filter | The tf2_ros::MessageFilter to connect to. |
display | The Display using the filter. |
FrameManager has internal functions for handling success and failure of tf2_ros::MessageFilters which call Display::setStatus() based on success or failure of the filter, including appropriate error messages.
Definition at line 230 of file frame_manager.h.
|
optional |
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 103 of file frame_manager.cpp.
|
optional |
Enable/disable pause mode.
Definition at line 122 of file frame_manager.cpp.
|
optional |
Set synchronization mode (off/exact/approximate)
Definition at line 127 of file frame_manager.cpp.
|
optional |
Synchronize with given time.
Definition at line 135 of file frame_manager.cpp.
|
inlineoptional |
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 165 of file frame_manager.h.
|
optional |
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 245 of file frame_manager.cpp.
|
optional |
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 310 of file frame_manager.cpp.
|
optional |
Clear the internal cache.
Definition at line 70 of file frame_manager.cpp.
|
private |
Definition at line 379 of file frame_manager.h.
|
private |
Definition at line 378 of file frame_manager.h.
|
private |
Definition at line 393 of file frame_manager.h.
|
private |
Definition at line 382 of file frame_manager.h.
|
private |
Definition at line 384 of file frame_manager.h.
|
private |
Definition at line 392 of file frame_manager.h.
|
private |
Definition at line 386 of file frame_manager.h.
|
private |
Definition at line 389 of file frame_manager.h.
|
private |
Definition at line 381 of file frame_manager.h.