tf_publish.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 #
00003 # publish static tf which is set by SetDynamicTF service
00004 # publishing tf is uniquely by child_frame_id
00005 #
00006 # TODO: delete target tf
00007 #       check tf tree consistency
00008 #       change frequency by frame_id
00009 #
00010 import roslib; roslib.load_manifest('dynamic_tf_publisher')
00011 import rospy
00012 
00013 from dynamic_tf_publisher.srv import * # SetDynamicTF
00014 from geometry_msgs.msg import TransformStamped,Quaternion,Vector3
00015 import tf
00016 import tf.msg
00017 import thread
00018 import yaml
00019 import os
00020 if os.getenv('ROS_DISTRO') != 'electric' :
00021     import genpy
00022 
00023 class dynamic_tf_publisher:
00024     def __init__(self):
00025         self.pub_tf = rospy.Publisher("/tf", tf.msg.tfMessage)
00026         self.pub_tf_mine = rospy.Publisher("~tf", tf.msg.tfMessage)
00027         self.cur_tf = dict()
00028         self.original_parent = dict()
00029         self.listener = tf.TransformListener()
00030         self.tf_sleep_time = 1.0
00031         self.lockobj = thread.allocate_lock()
00032         rospy.Service('/set_dynamic_tf', SetDynamicTF, self.set_tf)
00033         rospy.Service('/assoc_tf', AssocTF, self.assoc)
00034         rospy.Service('/dissoc_tf', DissocTF, self.dissoc)
00035         rospy.Service('/delete_tf', DeleteTF, self.delete)
00036 
00037         self.use_cache = rospy.get_param('~use_cache', True)
00038         # check the cache
00039         if self.use_cache and rospy.has_param('dynamic_tf_publisher'+rospy.get_name()) :
00040             tfm = tf.msg.tfMessage()
00041             if os.getenv('ROS_DISTRO') != 'electric' :
00042                 genpy.message.fill_message_args(tfm,[yaml.load(rospy.get_param('dynamic_tf_publisher'+rospy.get_name()))])
00043             else :
00044                 roslib.message.fill_message_args(tfm,[yaml.load(rospy.get_param('dynamic_tf_publisher'+rospy.get_name()))])
00045             for pose in tfm.transforms :
00046                 self.cur_tf[pose.child_frame_id] = pose
00047             
00048 
00049     def publish_tf(self):
00050         self.lockobj.acquire()
00051         time = rospy.Time.now()
00052         tfm = tf.msg.tfMessage()
00053         for frame_id in self.cur_tf.keys():
00054             pose = self.cur_tf[frame_id]
00055             pose.header.stamp = time
00056             tfm.transforms.append(pose)
00057         self.pub_tf.publish(tfm)
00058         self.pub_tf_mine.publish(tfm)
00059         self.lockobj.release()
00060 
00061     def assoc(self,req):
00062         if (not self.cur_tf.has_key(req.child_frame)) or self.cur_tf[req.child_frame] == req.parent_frame:
00063             rospy.logwarn("unkown key %s" % (req.child_frame))
00064             return AssocTFResponse()
00065         rospy.loginfo("assoc %s -> %s"%(req.parent_frame, req.child_frame))
00066         self.listener.waitForTransform(req.parent_frame,
00067                                        req.child_frame,
00068                                        req.header.stamp, rospy.Duration(1.0))
00069         ts = TransformStamped()
00070         (trans,rot) = self.listener.lookupTransform(req.parent_frame, req.child_frame, req.header.stamp)
00071         ts.transform.translation = Vector3(*trans)
00072         ts.transform.rotation = Quaternion(*rot)
00073         ts.header.stamp = req.header.stamp
00074         ts.header.frame_id = req.parent_frame
00075         ts.child_frame_id = req.child_frame
00076         self.lockobj.acquire()
00077         self.original_parent[req.child_frame] = self.cur_tf[req.child_frame].header.frame_id
00078         self.cur_tf[req.child_frame] = ts
00079         self.lockobj.release()
00080         self.publish_tf()
00081         return AssocTFResponse()
00082 
00083     def dissoc(self,req):
00084         areq = None
00085         rospy.loginfo("dissoc TF %s" % (req.frame_id))
00086         self.lockobj.acquire()
00087         if self.original_parent.has_key(req.frame_id):
00088             areq = AssocTFRequest()
00089             areq.header = req.header
00090             areq.child_frame = req.frame_id
00091             areq.parent_frame = self.original_parent[req.frame_id]
00092         self.lockobj.release()
00093         if areq:
00094             self.assoc(areq)
00095             self.original_parent.pop(req.frame_id) # remove 
00096         return DissocTFResponse()
00097 
00098     def delete(self,req):
00099         rospy.loginfo("delete TF %s"%(req.header.frame_id))
00100         self.lockobj.acquire()
00101         if self.original_parent.has_key(req.header.frame_id):
00102             del self.original_parent[req.header.frame_id]
00103         if self.cur_tf.has_key(req.header.frame_id):
00104             del self.cur_tf[req.header.frame_id]
00105         self.lockobj.release()
00106         return DeleteTFResponse()
00107 
00108     def set_tf(self,req):
00109         self.lockobj.acquire()
00110         # if not assocd
00111         if not self.original_parent.has_key(req.cur_tf.child_frame_id):
00112             self.tf_sleep_time = 1.0/req.freq
00113             self.cur_tf[req.cur_tf.child_frame_id] = req.cur_tf
00114             print "Latch [%s]/[%shz]"%(req.cur_tf.child_frame_id,req.freq)
00115         self.lockobj.release()
00116         # set parameter
00117         if self.use_cache:
00118             time = rospy.Time.now()
00119             tfm = tf.msg.tfMessage()
00120             for frame_id in self.cur_tf.keys():
00121                 pose = self.cur_tf[frame_id]
00122                 pose.header.stamp = time
00123                 tfm.transforms.append(pose)
00124             rospy.set_param('dynamic_tf_publisher'+rospy.get_name(),tfm.__str__())
00125         return SetDynamicTFResponse()
00126 
00127     def publish_and_sleep(self):
00128         self.publish_tf()
00129         rospy.sleep(self.tf_sleep_time)
00130 
00131 
00132 if __name__ == "__main__":
00133     rospy.init_node('tf_publish_server')
00134     pub = dynamic_tf_publisher()
00135     while not rospy.is_shutdown():
00136         pub.publish_and_sleep()
00137     print "exit"
00138 


dynamic_tf_publisher
Author(s): Manabu Saito
autogenerated on Mon Oct 6 2014 10:49:23