dynamixel_joint_state_publisher.py 3.4 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394
  1. #!/usr/bin/env python
  2. """
  3. dynamixel_joint_state_publisher.py - Version 1.1 2013-12-20
  4. Publish the dynamixel_controller joint states on the /joint_states topic
  5. Created for the Pi Robot Project: http://www.pirobot.org
  6. Copyright (c) 2010 Patrick Goebel. All rights reserved.
  7. This program is free software; you can redistribute it and/or modify
  8. it under the terms of the GNU General Public License as published by
  9. the Free Software Foundation; either version 2 of the License, or
  10. (at your option) any later version.
  11. This program is distributed in the hope that it will be useful,
  12. but WITHOUT ANY WARRANTY; without even the implied warranty of
  13. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  14. GNU General Public License for more details at:
  15. http://www.gnu.org/licenses/gpl.html
  16. """
  17. import rospy
  18. from sensor_msgs.msg import JointState as JointStatePR2
  19. from dynamixel_msgs.msg import JointState as JointStateDynamixel
  20. class JointStateMessage():
  21. def __init__(self, name, position, velocity, effort):
  22. self.name = name
  23. self.position = position
  24. self.velocity = velocity
  25. self.effort = effort
  26. class JointStatePublisher():
  27. def __init__(self):
  28. rospy.init_node('dynamixel_joint_state_publisher', anonymous=True)
  29. rate = rospy.get_param('~rate', 20)
  30. r = rospy.Rate(rate)
  31. # The namespace and joints parameter needs to be set by the servo controller
  32. # (The namespace is usually null.)
  33. namespace = rospy.get_namespace()
  34. self.joints = rospy.get_param(namespace + '/joints', '')
  35. self.servos = list()
  36. self.controllers = list()
  37. self.joint_states = dict({})
  38. for controller in sorted(self.joints):
  39. self.joint_states[controller] = JointStateMessage(controller, 0.0, 0.0, 0.0)
  40. self.controllers.append(controller)
  41. # Start controller state subscribers
  42. [rospy.Subscriber(c + '/state', JointStateDynamixel, self.controller_state_handler) for c in self.controllers]
  43. # Start publisher
  44. self.joint_states_pub = rospy.Publisher('/joint_states', JointStatePR2, queue_size=5)
  45. rospy.loginfo("Starting Dynamixel Joint State Publisher at " + str(rate) + "Hz")
  46. while not rospy.is_shutdown():
  47. self.publish_joint_states()
  48. r.sleep()
  49. def controller_state_handler(self, msg):
  50. js = JointStateMessage(msg.name, msg.current_pos, msg.velocity, msg.load)
  51. self.joint_states[msg.name] = js
  52. def publish_joint_states(self):
  53. # Construct message & publish joint states
  54. msg = JointStatePR2()
  55. msg.name = []
  56. msg.position = []
  57. msg.velocity = []
  58. msg.effort = []
  59. for joint in self.joint_states.values():
  60. msg.name.append(joint.name)
  61. msg.position.append(joint.position)
  62. msg.velocity.append(joint.velocity)
  63. msg.effort.append(joint.effort)
  64. msg.header.stamp = rospy.Time.now()
  65. msg.header.frame_id = 'base_link'
  66. self.joint_states_pub.publish(msg)
  67. if __name__ == '__main__':
  68. try:
  69. s = JointStatePublisher()
  70. rospy.spin()
  71. except rospy.ROSInterruptException: pass