odom_ekf.py 2.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263
  1. #!/usr/bin/env python
  2. """ odom_ekf.py - Version 1.1 2013-12-20
  3. Republish the /robot_pose_ekf/odom_combined topic which is of type
  4. geometry_msgs/PoseWithCovarianceStamped as an equivalent message of
  5. type nav_msgs/Odometry so we can view it in RViz.
  6. Created for the Pi Robot Project: http://www.pirobot.org
  7. Copyright (c) 2012 Patrick Goebel. All rights reserved.
  8. This program is free software; you can redistribute it and/or modify
  9. it under the terms of the GNU General Public License as published by
  10. the Free Software Foundation; either version 2 of the License, or
  11. (at your option) any later version.5
  12. This program is distributed in the hope that it will be useful,
  13. but WITHOUT ANY WARRANTY; without even the implied warranty of
  14. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  15. GNU General Public License for more details at:
  16. http://www.gnu.org/licenses/gpl.html
  17. """
  18. import rospy
  19. from geometry_msgs.msg import PoseWithCovarianceStamped
  20. from nav_msgs.msg import Odometry
  21. class OdomEKF():
  22. def __init__(self):
  23. # Give the node a name
  24. rospy.init_node('odom_ekf', anonymous=False)
  25. # Publisher of type nav_msgs/Odometry
  26. self.ekf_pub = rospy.Publisher('output', Odometry, queue_size=5)
  27. # Wait for the /odom_combined topic to become available
  28. rospy.wait_for_message('input', PoseWithCovarianceStamped)
  29. # Subscribe to the /odom_combined topic
  30. rospy.Subscriber('input', PoseWithCovarianceStamped, self.pub_ekf_odom)
  31. rospy.loginfo("Publishing combined odometry on /odom_ekf")
  32. def pub_ekf_odom(self, msg):
  33. odom = Odometry()
  34. odom.header = msg.header
  35. odom.header.frame_id = '/odom'
  36. odom.child_frame_id = 'base_footprint'
  37. odom.pose = msg.pose
  38. self.ekf_pub.publish(odom)
  39. if __name__ == '__main__':
  40. try:
  41. OdomEKF()
  42. rospy.spin()
  43. except:
  44. pass