ConstantHeightFramePublisher.py
Go to the documentation of this file.
00001 #! /usr/bin/env python
00002 # license removed for brevity
00003 import rospy
00004 from nav_msgs.msg import Odometry
00005 from std_msgs.msg import Float64
00006 
00007 import tf
00008 import numpy
00009 
00010 class ConstantHeightFramePublisher:
00011     def __init__(self):
00012         rospy.init_node("ConstantHeightFramePublisher", anonymous=True)
00013         self.sub = rospy.Subscriber("~height", Float64, self.height_callback)
00014         self.broadcast = tf.TransformBroadcaster()
00015         self.listener = tf.TransformListener()
00016         self.rate = rospy.Rate(rospy.get_param("~rate", 10.0)) # [Hz]
00017         self.height = rospy.get_param("~height", 1.0) # [m]
00018         self.parent = rospy.get_param("~parent_frame", "BODY")
00019         self.frame_name = rospy.get_param("~frame_name", "pointcloud_to_scan_base")
00020 
00021     def execute(self):
00022         while not rospy.is_shutdown():
00023             self.make_constant_tf()
00024             self.rate.sleep()
00025 
00026     def height_callback(self, msg):
00027         self.height = msg.data
00028 
00029     def make_constant_tf(self):
00030         try:
00031             (trans,rot) = self.listener.lookupTransform(self.parent, '/odom', rospy.Time(0))
00032             # transformation: (x, y): same as parent, z: equal to height
00033             T = tf.transformations.quaternion_matrix(rot)
00034             T[:3, 3] = trans
00035             T_inv = tf.transformations.inverse_matrix(T)
00036             target_trans = T.dot(numpy.array([T_inv[:3, 3][0], T_inv[:3, 3][1], self.height, 1]))[:3]
00037             # rotation: (x, y): same as /odom, z: same as parent 
00038             rot_euler = tf.transformations.euler_from_quaternion(rot)
00039             target_rot = tf.transformations.quaternion_from_euler(rot_euler[0], rot_euler[1], 0.0)
00040             # publish tf
00041             self.broadcast.sendTransform(target_trans, target_rot, rospy.Time.now(), self.frame_name, self.parent)
00042         except (tf.LookupException, tf.ConnectivityException, tf.ExtrapolationException):
00043             return
00044 
00045 if __name__ == '__main__':
00046     try:
00047         node = ConstantHeightFramePublisher()
00048         node.execute()
00049     except rospy.ROSInterruptException: pass


jsk_robot_startup
Author(s):
autogenerated on Wed Sep 16 2015 10:31:26