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 #ifndef _STATIC_TRANSFORM_BROADCASTER_H_ 00034 #define _STATIC_TRANSFORM_BROADCASTER_H_ 00035 00036 #include <map> 00037 00038 #include <boost/thread/thread.hpp> 00039 #include <boost/thread/mutex.hpp> 00040 00041 #include <geometry_msgs/TransformStamped.h> 00042 00043 #include <tf/transform_datatypes.h> 00044 #include <tf/transform_broadcaster.h> 00045 00046 namespace static_transform_broadcaster { 00047 00049 00058 class StaticTransformBroadcaster 00059 { 00060 private: 00062 tf::TransformBroadcaster broadcaster_; 00063 00065 std::map<std::string, geometry_msgs::TransformStamped> transforms_; 00066 00068 double publishing_rate_; 00069 00071 bool finished_; 00072 00074 boost::thread *publishing_thread_; 00075 00077 boost::mutex mutex_; 00078 00081 void publishingThread() 00082 { 00083 while (!finished_) 00084 { 00085 ros::Duration(publishing_rate_).sleep(); 00086 std::map<std::string, geometry_msgs::TransformStamped>::iterator it; 00087 mutex_.lock(); 00088 for (it = transforms_.begin(); it!=transforms_.end(); it++) 00089 { 00090 geometry_msgs::TransformStamped trans = it->second; 00091 trans.header.stamp = ros::Time::now(); 00092 broadcaster_.sendTransform(trans); 00093 } 00094 mutex_.unlock(); 00095 } 00096 } 00097 00098 public: 00100 StaticTransformBroadcaster() : publishing_rate_(0.1), finished_(false) 00101 { 00102 publishing_thread_ = new boost::thread(boost::bind(&StaticTransformBroadcaster::publishingThread, this)); 00103 } 00104 00106 ~StaticTransformBroadcaster() 00107 { 00108 finished_ = true; 00109 publishing_thread_->join(); 00110 delete publishing_thread_; 00111 } 00112 00114 00115 void setTransform(geometry_msgs::TransformStamped transform) 00116 { 00117 mutex_.lock(); 00118 transforms_[transform.child_frame_id] = transform; 00119 mutex_.unlock(); 00120 } 00121 00123 void removeTransform(std::string child_frame_id) 00124 { 00125 mutex_.lock(); 00126 std::map<std::string, geometry_msgs::TransformStamped>::iterator it = transforms_.find(child_frame_id); 00127 if (it != transforms_.end()) 00128 { 00129 transforms_.erase(it); 00130 } 00131 else 00132 { 00133 ROS_WARN("Static transform broadcaster: attempt to erase non-existent transform to frame %s", 00134 child_frame_id.c_str()); 00135 } 00136 mutex_.unlock(); 00137 } 00138 00140 void removeAllTransforms() 00141 { 00142 transforms_.clear(); 00143 } 00144 00146 void setPublishingRate(double rate) 00147 { 00148 publishing_rate_ = std::max(0.0, rate); 00149 } 00150 00151 double getPublishingRate() const 00152 { 00153 return publishing_rate_; 00154 } 00155 }; 00156 00157 } //namespace 00158 00159 #endif 00160