relax_all_servos.py 3.0 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980
  1. #!/usr/bin/env python
  2. """
  3. relax_all_servos.py - Version 1.1 2013-12-20
  4. Relax all servos by disabling the torque and setting the speed
  5. and torque limit to a moderate values.
  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. import time
  20. from dynamixel_controllers.srv import TorqueEnable, SetTorqueLimit, SetSpeed
  21. class Relax():
  22. def __init__(self):
  23. rospy.init_node('relax_all_servos')
  24. # The namespace and joints parameter needs to be set by the servo controller
  25. # (The namespace is usually null.)
  26. namespace = rospy.get_namespace()
  27. self.joints = rospy.get_param(namespace + '/joints', '')
  28. default_dynamixel_speed = rospy.get_param('~default_dynamixel_speed', 0.5)
  29. default_dynamixel_torque = rospy.get_param('~default_dynamixel_torque', 0.5)
  30. speed_services = list()
  31. torque_services = list()
  32. set_torque_limit_services = list()
  33. for controller in sorted(self.joints):
  34. torque_service = '/' + controller + '/torque_enable'
  35. rospy.wait_for_service(torque_service)
  36. torque_services.append(rospy.ServiceProxy(torque_service, TorqueEnable))
  37. set_torque_limit_service = '/' + controller + '/set_torque_limit'
  38. rospy.wait_for_service(set_torque_limit_service)
  39. set_torque_limit_services.append(rospy.ServiceProxy(set_torque_limit_service, SetTorqueLimit))
  40. speed_service = '/' + controller + '/set_speed'
  41. rospy.wait_for_service(speed_service)
  42. speed_services.append(rospy.ServiceProxy(speed_service, SetSpeed))
  43. # Set the default speed to something small
  44. for set_speed in speed_services:
  45. try:
  46. set_speed(default_dynamixel_speed)
  47. except:
  48. pass
  49. # Set the torque limit to a moderate value
  50. for set_torque_limit in set_torque_limit_services:
  51. try:
  52. set_torque_limit(default_dynamixel_torque)
  53. except:
  54. pass
  55. # Relax all servos to give them a rest.
  56. for torque_enable in torque_services:
  57. try:
  58. torque_enable(False)
  59. except:
  60. pass
  61. if __name__=='__main__':
  62. Relax()