$search
00001 #!/usr/bin/python 00002 00003 # 00004 # Similar to static_transform_broadcaster, this node constantly publishes 00005 # static odometry information (Odometry msg and tf). This can be used 00006 # with fake_localization to evaluate planning algorithms without running 00007 # an actual robot with odometry or localization 00008 # 00009 # Author: Armin Hornung 00010 # License: BSD 00011 00012 import roslib 00013 roslib.load_manifest('fake_localization') 00014 import rospy 00015 00016 import tf 00017 from nav_msgs.msg import Odometry 00018 from geometry_msgs.msg import Pose, Quaternion, Point 00019 00020 def publishOdom(): 00021 rospy.init_node('fake_odom') 00022 base_frame_id = rospy.get_param("~base_frame_id", "base_link") 00023 odom_frame_id = rospy.get_param("~odom_frame_id", "odom") 00024 publish_frequency = rospy.get_param("~publish_frequency", 10.0) 00025 pub = rospy.Publisher('odom', Odometry) 00026 tf_pub = tf.TransformBroadcaster() 00027 00028 #TODO: static pose could be made configurable (cmd.line or parameters) 00029 quat = tf.transformations.quaternion_from_euler(0, 0, 0) 00030 00031 odom = Odometry() 00032 odom.header.frame_id = odom_frame_id 00033 odom.pose.pose = Pose(Point(0,0,0),Quaternion(*quat)) 00034 00035 rospy.loginfo("Publishing static odometry from \"%s\" to \"%s\"", odom_frame_id, base_frame_id) 00036 r = rospy.Rate(publish_frequency) 00037 while not rospy.is_shutdown(): 00038 odom.header.stamp = rospy.Time.now() 00039 pub.publish(odom) 00040 tf_pub.sendTransform((0,0,0), quat, 00041 odom.header.stamp, base_frame_id, odom_frame_id) 00042 r.sleep() 00043 00044 00045 if __name__ == '__main__': 00046 try: 00047 publishOdom() 00048 except rospy.ROSInterruptException: pass