Go to the documentation of this file.
   30 #ifndef RVIZ_FRAME_MANAGER_H 
   31 #define RVIZ_FRAME_MANAGER_H 
   39 #include <geometry_msgs/Pose.h> 
   42 #include <OgreQuaternion.h> 
   44 #include <boost/thread/mutex.hpp> 
   52 class TransformListener;
 
   77   explicit FrameManager(std::shared_ptr<tf2_ros::Buffer> tf_buffer = std::shared_ptr<tf2_ros::Buffer>(),
 
   78                         std::shared_ptr<tf2_ros::TransformListener> tf_listener =
 
   79                             std::shared_ptr<tf2_ros::TransformListener>());
 
  124   template <
typename Header>
 
  138                     Ogre::Vector3& position,
 
  139                     Ogre::Quaternion& orientation);
 
  147   template <
typename Header>
 
  149                  const geometry_msgs::Pose& pose,
 
  150                  Ogre::Vector3& position,
 
  151                  Ogre::Quaternion& orientation)
 
  165                  const geometry_msgs::Pose& pose,
 
  166                  Ogre::Vector3& position,
 
  167                  Ogre::Quaternion& orientation);
 
  196     filter->registerCallback(
 
  197         boost::bind(&FrameManager::messageCallback<M>, 
this, boost::placeholders::_1, display));
 
  199         boost::bind(&FrameManager::failureCallback<M, tf2_ros::FilterFailureReason>, 
this,
 
  200                     boost::placeholders::_1, boost::placeholders::_2, display));
 
  225                                     const std::string& caller_id,
 
  241     messageArrived(msg->header.frame_id, msg->header.stamp, authority, display);
 
  244   template <
class M, 
class TfFilterFailureReasonType>
 
  246                        TfFilterFailureReasonType reason,
 
  252     messageFailed(msg->header.frame_id, msg->header.stamp, authority, reason, display);
 
  257                       const std::string& caller_id,
 
  262   template <
class TfFilterFailureReasonType>
 
  265                      const std::string& caller_id,
 
  266                      TfFilterFailureReasonType reason,
 
  302   typedef std::map<CacheKey, CacheEntry> 
M_Cache;
 
  325 #endif // RVIZ_FRAME_MANAGER_H 
  
const std::shared_ptr< tf2_ros::Buffer > getTF2BufferPtr()
FrameManager(std::shared_ptr< tf2_ros::Buffer > tf_buffer=std::shared_ptr< tf2_ros::Buffer >(), std::shared_ptr< tf2_ros::TransformListener > tf_listener=std::shared_ptr< tf2_ros::TransformListener >())
Constructor, will create a TransformListener (and Buffer) automatically if not provided.
Helper class for transforming data into Ogre's world frame (the fixed frame).
void messageArrived(const std::string &frame_id, const ros::Time &stamp, const std::string &caller_id, Display *display)
void messageCallback(const ros::MessageEvent< M const > &msg_evt, Display *display)
message_filters::Connection registerFailureCallback(const FailureCallback &callback)
boost::mutex cache_mutex_
void setFixedFrame(const std::string &frame)
Set the frame to consider "fixed", into which incoming data is transformed.
void fixedFrameChanged()
Emitted whenever the fixed frame changes.
void adjustTime(ros::Time &time)
const std::string & getPublisherName() const
CacheEntry(const Ogre::Vector3 &p, const Ogre::Quaternion &o)
const boost::shared_ptr< ConstMessage > & getConstMessage() const
void messageFailed(const std::string &frame_id, const ros::Time &stamp, const std::string &caller_id, TfFilterFailureReasonType reason, Display *display)
CacheKey(const std::string &f, ros::Time t)
void setSyncMode(SyncMode mode)
Set synchronization mode (off/exact/approximate)
ros::Time getTime()
Get current time, depending on the sync mode.
const std::string & getFixedFrame()
Return the current fixed frame name.
std::shared_ptr< tf2_ros::TransformListener > tf_listener_
void messageFailedImpl(const std::string &caller_id, const std::string &status_text, Display *display)
void failureCallback(const ros::MessageEvent< M const > &msg_evt, TfFilterFailureReasonType reason, Display *display)
Ogre::Quaternion orientation
~FrameManager() override
Destructor.
bool frameHasProblems(const std::string &frame, ros::Time time, std::string &error)
Check to see if a frame exists in our tf buffer.
void syncTime(ros::Time time)
Synchronize with given time.
std::map< CacheKey, CacheEntry > M_Cache
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.
void registerFilterForTransformStatusCheck(tf2_ros::MessageFilter< M > *filter, Display *display)
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.
void update()
Clear the internal cache.
bool operator<(const CacheKey &rhs) const
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.
geometry_msgs::TransformStamped t
std::shared_ptr< tf2_ros::Buffer > tf_buffer_
void setPause(bool pause)
Enable/disable pause mode.
std::string discoverFailureReason(const std::string &frame_id, const ros::Time &stamp, const std::string &caller_id, tf2_ros::FilterFailureReason reason)
rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall 
autogenerated on Sun May 4 2025 02:31:26