30 #ifndef RVIZ_FRAME_MANAGER_H 31 #define RVIZ_FRAME_MANAGER_H 39 #include <geometry_msgs/Pose.h> 41 #include <OgreVector3.h> 42 #include <OgreQuaternion.h> 44 #include <boost/thread/mutex.hpp> 52 class TransformListener;
64 class FrameManager :
public QObject
76 explicit FrameManager(std::shared_ptr<tf2_ros::Buffer> tf_buffer = std::shared_ptr<tf2_ros::Buffer>(),
77 std::shared_ptr<tf2_ros::TransformListener> tf_listener =
78 std::shared_ptr<tf2_ros::TransformListener>());
85 ~FrameManager()
override;
91 void setFixedFrame(
const std::string& frame);
94 void setPause(
bool pause);
102 void setSyncMode(SyncMode mode);
104 SyncMode getSyncMode()
123 template <
typename Header>
124 bool getTransform(
const Header& header, Ogre::Vector3& position, Ogre::Quaternion& orientation)
126 return getTransform(header.frame_id, header.
stamp, position, orientation);
135 bool getTransform(
const std::string& frame,
137 Ogre::Vector3& position,
138 Ogre::Quaternion& orientation);
146 template <
typename Header>
147 bool transform(
const Header& header,
148 const geometry_msgs::Pose& pose,
149 Ogre::Vector3& position,
150 Ogre::Quaternion& orientation)
152 return transform(header.frame_id, header.
stamp, pose, position, orientation);
162 bool transform(
const std::string& frame,
164 const geometry_msgs::Pose& pose,
165 Ogre::Vector3& position,
166 Ogre::Quaternion& orientation);
176 bool frameHasProblems(
const std::string& frame,
ros::Time time, std::string& error);
183 bool transformHasProblems(
const std::string& frame,
ros::Time time, std::string& error);
195 filter->
registerCallback(boost::bind(&FrameManager::messageCallback<M>,
this, _1, display));
197 &FrameManager::failureCallback<M, tf2_ros::FilterFailureReason>,
this, _1, _2, display));
201 const std::string& getFixedFrame()
206 const std::shared_ptr<tf2_ros::Buffer> getTF2BufferPtr()
220 std::string discoverFailureReason(
const std::string& frame_id,
222 const std::string& caller_id,
227 void fixedFrameChanged();
230 bool adjustTime(
const std::string& frame,
ros::Time& time);
239 messageArrived(msg->info.header.frame_id, msg->info.header.stamp, authority, display);
242 template <
class M,
class TfFilterFailureReasonType>
244 TfFilterFailureReasonType reason,
251 messageFailed(msg->info.header.frame_id, msg->info.header.stamp, authority, reason, display);
254 void messageArrived(
const std::string& frame_id,
256 const std::string& caller_id,
259 void messageFailedImpl(
const std::string& caller_id,
const std::string& status_text, Display* display);
261 template <
class TfFilterFailureReasonType>
262 void messageFailed(
const std::string& frame_id,
264 const std::string& caller_id,
265 TfFilterFailureReasonType reason,
268 std::string status_text = discoverFailureReason(frame_id, stamp, caller_id, reason);
269 messageFailedImpl(caller_id, status_text, display);
274 CacheKey(
const std::string& f,
ros::Time t) : frame(f), time(t)
278 bool operator<(
const CacheKey& rhs)
const 280 if (frame != rhs.frame)
282 return frame < rhs.frame;
285 return time < rhs.time;
294 CacheEntry(
const Ogre::Vector3& p,
const Ogre::Quaternion& o) : position(p), orientation(o)
298 Ogre::Vector3 position;
299 Ogre::Quaternion orientation;
301 typedef std::map<CacheKey, CacheEntry> M_Cache;
303 boost::mutex cache_mutex_;
306 std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
307 std::shared_ptr<tf2_ros::TransformListener> tf_listener_;
308 std::string fixed_frame_;
320 double current_delta_;
325 #endif // RVIZ_FRAME_MANAGER_H
message_filters::Connection registerFailureCallback(const FailureCallback &callback)
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
const std::string & getPublisherName() const
const boost::shared_ptr< ConstMessage > & getConstMessage() const
Connection registerCallback(const C &callback)