$search
00001 /********************************************************************* 00002 * 00003 * Copyright (c) 2009, Willow Garage, Inc. 00004 * All rights reserved. 00005 * 00006 * Redistribution and use in source and binary forms, with or without 00007 * modification, are permitted provided that the following conditions 00008 * are met: 00009 * 00010 * * Redistributions of source code must retain the above copyright 00011 * notice, this list of conditions and the following disclaimer. 00012 * * Redistributions in binary form must reproduce the above 00013 * copyright notice, this list of conditions and the following 00014 * disclaimer in the documentation and/or other materials provided 00015 * with the distribution. 00016 * * Neither the name of the Willow Garage nor the names of its 00017 * contributors may be used to endorse or promote products derived 00018 * from this software without specific prior written permission. 00019 * 00020 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00021 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00022 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00023 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00024 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00025 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00026 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00027 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00028 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00029 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00030 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00031 * POSSIBILITY OF SUCH DAMAGE. 00032 *********************************************************************/ 00033 00034 #include <boost/thread/mutex.hpp> 00035 00036 #include <map> 00037 00038 #include <ros/ros.h> 00039 #include <tf/tfMessage.h> 00040 #include <tf/transform_datatypes.h> 00041 00042 #include <geometry_msgs/PoseStamped.h> 00043 00044 namespace pr2_interactive_manipulation 00045 { 00046 00047 class TFThrottle 00048 { 00049 protected: 00050 00051 class TransformInfo { 00052 public: 00053 geometry_msgs::TransformStamped transform_; 00054 bool changed_; 00055 ros::Time last_published_; 00056 00057 TransformInfo(geometry_msgs::TransformStamped trf) 00058 { 00059 changed_ = true; 00060 last_published_ = ros::Time(0); 00061 transform_ = trf; 00062 } 00063 }; 00064 00065 std::map<std::string, TransformInfo> transforms_; 00066 ros::NodeHandle root_nh_; 00067 ros::NodeHandle priv_nh_; 00068 ros::Publisher pub_; 00069 ros::Subscriber sub_; 00070 boost::mutex mutex_; 00071 ros::Timer sync_timer_; 00072 ros::Duration republish_time_; 00073 double linear_change_threshold_; 00074 double angular_change_threshold_; 00075 00076 bool changed(const geometry_msgs::TransformStamped &t1, 00077 const geometry_msgs::TransformStamped &t2) 00078 { 00079 tf::Transform tf1, tf2; 00080 tf::transformMsgToTF(t1.transform, tf1); 00081 tf::transformMsgToTF(t2.transform, tf2); 00082 00083 if (linear_change_threshold_ == 0.0 || angular_change_threshold_ == 0.0 || 00084 tf1.getOrigin().distance(tf2.getOrigin()) > linear_change_threshold_ || 00085 tf1.getRotation().angle(tf2.getRotation()) > angular_change_threshold_) return true; 00086 return false; 00087 } 00088 00089 void callback(const tf::tfMessageConstPtr &msg) 00090 { 00091 boost::mutex::scoped_lock lock(mutex_); 00092 for (size_t i=0; i<msg->transforms.size(); i++) 00093 { 00094 std::string key = msg->transforms[i].header.frame_id + msg->transforms[i].child_frame_id; 00095 std::map<std::string, TransformInfo>::iterator it = transforms_.find(key); 00096 if (it == transforms_.end()) 00097 { 00098 transforms_.insert( std::pair<std::string, TransformInfo>(key, TransformInfo(msg->transforms[i])) ); 00099 } 00100 else 00101 { 00102 ros::Time tf_time(msg->transforms[i].header.stamp); 00103 if (it->second.changed_ && msg->transforms[i].header.stamp > it->second.transform_.header.stamp) 00104 { 00105 it->second.transform_ = msg->transforms[i]; 00106 } 00107 else if (ros::Duration(tf_time - it->second.last_published_) > ros::Duration(republish_time_)) 00108 { 00109 it->second.transform_ = msg->transforms[i]; 00110 it->second.changed_ = true; 00111 } 00112 else if ( changed(it->second.transform_, msg->transforms[i]) ) 00113 { 00114 ROS_DEBUG_STREAM("Transform has changed: " << key); 00115 it->second.transform_ = msg->transforms[i]; 00116 it->second.changed_ = true; 00117 } 00118 } 00119 } 00120 } 00121 00122 void sync() 00123 { 00124 boost::mutex::scoped_lock lock(mutex_); 00125 if (transforms_.empty()) return; 00126 tf::tfMessage msg; 00127 std::map<std::string, TransformInfo>::iterator it; 00128 for (it=transforms_.begin(); it!=transforms_.end(); it++) 00129 { 00130 if (it->second.changed_) 00131 { 00132 it->second.changed_ = false; 00133 it->second.last_published_ = ros::Time(it->second.transform_.header.stamp); 00134 msg.transforms.push_back(it->second.transform_); 00135 } 00136 } 00137 pub_.publish(msg); 00138 } 00139 00140 public: 00141 TFThrottle() : root_nh_(""), priv_nh_("~") 00142 { 00143 std::string pub_topic; 00144 priv_nh_.param<std::string>("publish_topic", pub_topic, "/tf_throttled"); 00145 pub_ = root_nh_.advertise<tf::tfMessage>(pub_topic, 10); 00146 std::string sub_topic; 00147 priv_nh_.param<std::string>("subscribe_topic", sub_topic, "/tf"); 00148 sub_ = root_nh_.subscribe(sub_topic, 10, &TFThrottle::callback, this); 00149 double rate; 00150 priv_nh_.param<double>("rate", rate, 10.0); 00151 sync_timer_ = root_nh_.createTimer(ros::Duration(1.0/rate), boost::bind( &TFThrottle::sync, this ) ); 00152 double repub_time; 00153 priv_nh_.param<double>("republish_time", repub_time, 0.5); 00154 republish_time_ = ros::Duration(repub_time); 00155 priv_nh_.param<double>("angular_change_threshold", angular_change_threshold_, 0.02); 00156 priv_nh_.param<double>("linear_change_threshold", linear_change_threshold_, 1.0); 00157 ROS_INFO("TF throttle started; listening to %s and publishing on %s at %f Hz", sub_topic.c_str(), 00158 pub_topic.c_str(), rate); 00159 } 00160 }; 00161 00162 } 00163 00164 int main(int argc, char **argv) 00165 { 00166 ros::init(argc, argv, "tf_throttle"); 00167 pr2_interactive_manipulation::TFThrottle throttle; 00168 ros::spin(); 00169 return 0; 00170 }