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> 49 #include <type_traits> 54 #if ROS_VERSION_MINIMUM(1,14,0) 57 class TransformListener;
62 class TransformListener;
74 class FrameManager:
public QObject
79 using TransformListener = std::conditional<ROS_VERSION_MINIMUM(1,14,0), tf2_ros::TransformListener, tf::TransformListener>::type;
80 using FilterFailureReason = std::conditional<ROS_VERSION_MINIMUM(1,14,0), tf2_ros::FilterFailureReason, tf::FilterFailureReason>::type;
81 #if ROS_VERSION_MINIMUM(1,14,0) 82 template <
class message_type>
85 template <
class message_type>
111 void setFixedFrame(
const std::string& frame);
114 void setPause(
bool pause );
116 bool getPause() {
return pause_; }
119 void setSyncMode( SyncMode mode );
121 SyncMode getSyncMode() {
return sync_mode_; }
127 ros::Time getTime() {
return sync_time_; }
134 template<
typename Header>
135 bool getTransform(
const Header& header, Ogre::Vector3& position, Ogre::Quaternion& orientation)
137 return getTransform(header.frame_id, header.
stamp, position, orientation);
146 bool getTransform(
const std::string& frame,
ros::Time time, Ogre::Vector3& position, Ogre::Quaternion& orientation);
154 template<
typename Header>
155 bool transform(
const Header& header,
const geometry_msgs::Pose& pose, Ogre::Vector3& position, Ogre::Quaternion& orientation)
157 return transform(header.frame_id, header.
stamp, pose, position, orientation);
167 bool transform(
const std::string& frame,
ros::Time time,
const geometry_msgs::Pose& pose, Ogre::Vector3& position, Ogre::Quaternion& orientation);
177 bool frameHasProblems(
const std::string& frame,
ros::Time time, std::string& error);
184 bool transformHasProblems(
const std::string& frame,
ros::Time time, std::string& error);
195 void registerFilterForTransformStatusCheck(MessageFilter<M>* filter, Display* display)
197 filter->registerCallback(boost::bind(&FrameManager::messageCallback<M>,
this, _1, display));
198 filter->registerFailureCallback(boost::bind(&FrameManager::failureCallback<M>,
this, _1, _2, display));
202 const std::string& getFixedFrame() {
return fixed_frame_; }
205 TransformListener* getTFClient() {
return tf_.get(); }
219 std::string discoverFailureReason(
const std::string& frame_id,
221 const std::string& caller_id,
226 void fixedFrameChanged();
230 bool adjustTime(
const std::string &frame,
ros::Time &time );
238 messageArrived(msg->info.header.frame_id, msg->info.header.stamp, authority, display);
247 messageFailed(msg->info.header.frame_id, msg->info.header.stamp, authority, reason, display);
250 void messageArrived(
const std::string& frame_id,
const ros::Time& stamp,
const std::string& caller_id, Display* display);
251 void messageFailed(
const std::string& frame_id,
const ros::Time& stamp,
const std::string& caller_id,
FilterFailureReason reason, Display* display);
255 CacheKey(
const std::string& f,
ros::Time t)
260 bool operator<(
const CacheKey& rhs)
const 262 if (frame != rhs.frame)
264 return frame < rhs.frame;
267 return time < rhs.time;
276 CacheEntry(
const Ogre::Vector3& p,
const Ogre::Quaternion& o)
281 Ogre::Vector3 position;
282 Ogre::Quaternion orientation;
284 typedef std::map<CacheKey, CacheEntry > M_Cache;
286 boost::mutex cache_mutex_;
290 std::string fixed_frame_;
301 double current_delta_;
306 #endif // RVIZ_FRAME_MANAGER_H
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
const std::string & getPublisherName() const
const boost::shared_ptr< ConstMessage > & getConstMessage() const