30 #ifndef RVIZ_FRAME_MANAGER_H 31 #define RVIZ_FRAME_MANAGER_H 39 #include <OgreVector3.h> 40 #include <OgreQuaternion.h> 42 #include <boost/thread/mutex.hpp> 44 #include <geometry_msgs/Pose.h> 52 class TransformListener;
90 void setFixedFrame(
const std::string& frame);
93 void setPause(
bool pause );
113 template<
typename Header>
116 return getTransform(header.frame_id, header.
stamp, position, orientation);
125 bool getTransform(
const std::string& frame,
ros::Time time, Ogre::Vector3& position, Ogre::Quaternion& orientation);
133 template<
typename Header>
134 bool transform(
const Header& header,
const geometry_msgs::Pose& pose, Ogre::Vector3& position, Ogre::Quaternion& orientation)
136 return transform(header.frame_id, header.
stamp, pose, position, orientation);
146 bool transform(
const std::string& frame,
ros::Time time,
const geometry_msgs::Pose& pose, Ogre::Vector3& position, Ogre::Quaternion& orientation);
156 bool frameHasProblems(
const std::string& frame,
ros::Time time, std::string& error);
163 bool transformHasProblems(
const std::string& frame,
ros::Time time, std::string& error);
176 filter->
registerCallback(boost::bind(&FrameManager::messageCallback<M>,
this, _1, display));
198 std::string discoverFailureReason(
const std::string& frame_id,
200 const std::string& caller_id,
205 void fixedFrameChanged();
209 bool adjustTime(
const std::string &frame,
ros::Time &time );
217 messageArrived(msg->header.frame_id, msg->header.stamp, authority, display);
226 messageFailed(msg->header.frame_id, msg->header.stamp, authority, reason, display);
229 void messageArrived(
const std::string& frame_id,
const ros::Time& stamp,
const std::string& caller_id,
Display* display);
241 if (frame != rhs.
frame)
243 return frame < rhs.
frame;
246 return time < rhs.
time;
255 CacheEntry(
const Ogre::Vector3& p,
const Ogre::Quaternion& o)
263 typedef std::map<CacheKey, CacheEntry >
M_Cache;
285 #endif // RVIZ_FRAME_MANAGER_H void failureCallback(const ros::MessageEvent< M const > &msg_evt, tf::FilterFailureReason reason, Display *display)
Ogre::Quaternion orientation
boost::mutex cache_mutex_
boost::shared_ptr< tf::TransformListener > tf_
ros::Time getTime()
Get current time, depending on the sync mode.
CacheKey(const std::string &f, ros::Time t)
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
const std::string & getPublisherName() const
const boost::shared_ptr< ConstMessage > & getConstMessage() const
Helper class for transforming data into Ogre's world frame (the fixed frame).
const boost::shared_ptr< tf::TransformListener > & getTFClientPtr()
Return a boost shared pointer to the tf::TransformListener used to receive transform data...
void registerFilterForTransformStatusCheck(tf::MessageFilter< M > *filter, Display *display)
Connect a tf::MessageFilter's callbacks to success and failure handler functions in this FrameManager...
message_filters::Connection registerFailureCallback(const FailureCallback &callback)
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.
tf::TransformListener * getTFClient()
Return the tf::TransformListener used to receive transform data.
const std::string & getFixedFrame()
Return the current fixed frame name.
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 operator<(const CacheKey &rhs) const
void messageCallback(const ros::MessageEvent< M const > &msg_evt, Display *display)
std::map< CacheKey, CacheEntry > M_Cache
CacheEntry(const Ogre::Vector3 &p, const Ogre::Quaternion &o)
Connection registerCallback(const C &callback)