00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036 #ifndef SCENE_MANAGER_H_
00037 #define SCENE_MANAGER_H_
00038
00039 #include <map>
00040 #include <ros/ros.h>
00041 #include <boost/thread/mutex.hpp>
00042 #include <wviz_tf_manager/PublishAllTransforms.h>
00043 #include <tf/transform_listener.h>
00044 #include <XmlRpcValue.h>
00045
00046 namespace wviz_tf_manager {
00047
00048 class FramePair
00049 {
00050 public:
00051 FramePair(const std::string& source_frame, const std::string& target_frame, double translational_update_distance, double angular_update_distance) :
00052 source_frame_(source_frame),
00053 target_frame_(target_frame),
00054 translational_update_distance_(translational_update_distance),
00055 angular_update_distance_(angular_update_distance)
00056 {
00057 pose_in_ = tf::Stamped<tf::Pose>(tf::Pose(tf::createIdentityQuaternion(), tf::Vector3(0, 0, 0)), ros::Time(), source_frame_);
00058 }
00059
00060 public:
00061 std::string source_frame_;
00062 std::string target_frame_;
00063
00064 tf::Stamped<tf::Pose> pose_in_;
00065 tf::Stamped<tf::Pose> pose_out_;
00066 tf::Stamped<tf::Pose> last_sent_pose_;
00067
00068 double translational_update_distance_;
00069 double angular_update_distance_;
00070 };
00071
00076 class TransformManager {
00077 public:
00082 TransformManager(ros::NodeHandle& node);
00083
00087 virtual ~TransformManager();
00088
00092 bool publishAllTransforms(wviz_tf_manager::PublishAllTransforms::Request& req, wviz_tf_manager::PublishAllTransforms::Response& resp);
00093
00097 void spin();
00098
00102 void tfCallback(const tf::tfMessageConstPtr& msg_ptr);
00103
00104 void publishAll();
00105 void publishChanged();
00106
00107 private:
00108 ros::NodeHandle node_;
00109 double polling_frequency_;
00110 double translational_update_distance_;
00111 double angular_update_distance_;
00112
00113 boost::mutex frame_pairs_mutex_;
00114 std::map<std::string,FramePair> frame_pairs_;
00115 tf::TransformListener tfl_;
00116 ros::Publisher pub_;
00117
00118 bool publish_all_;
00119 ros::ServiceServer publish_all_srv_;
00120 ros::Subscriber subscriber_tf_;
00121 };
00122
00123 }
00124
00125 #endif
00126