You can not select more than 25 topics Topics must start with a chinese character,a letter or number, can include dashes ('-') and can be up to 35 characters long.

dynamixel.py 18 kB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535
  1. """Module for managing Dynamixel servo communication and control.
  2. This module provides functionality for communicating with and controlling Dynamixel servos
  3. through a serial interface. It includes methods for reading and writing servo parameters,
  4. managing operating modes, and handling joint positions and velocities.
  5. """
  6. from __future__ import annotations
  7. import enum
  8. import math
  9. import os
  10. import time
  11. from dataclasses import dataclass
  12. from dynamixel_sdk import * # Uses Dynamixel SDK library
  13. class ReadAttribute(enum.Enum):
  14. """Enumeration for Dynamixel servo read attributes."""
  15. TEMPERATURE = 146
  16. VOLTAGE = 145
  17. VELOCITY = 128
  18. POSITION = 132
  19. CURRENT = 126
  20. PWM = 124
  21. HARDWARE_ERROR_STATUS = 70
  22. HOMING_OFFSET = 20
  23. BAUDRATE = 8
  24. class OperatingMode(enum.Enum):
  25. """Enumeration for Dynamixel servo operating modes."""
  26. VELOCITY = 1
  27. POSITION = 3
  28. CURRENT_CONTROLLED_POSITION = 5
  29. PWM = 16
  30. UNKNOWN = -1
  31. class Dynamixel:
  32. """Class for managing communication with Dynamixel servos."""
  33. ADDR_TORQUE_ENABLE = 64
  34. ADDR_GOAL_POSITION = 116
  35. ADDR_VELOCITY_LIMIT = 44
  36. ADDR_GOAL_PWM = 100
  37. OPERATING_MODE_ADDR = 11
  38. POSITION_I = 82
  39. POSITION_P = 84
  40. ADDR_ID = 7
  41. @dataclass
  42. class Config:
  43. """Configuration class for Dynamixel servo settings."""
  44. def instantiate(self):
  45. """Create a new Dynamixel instance with this configuration."""
  46. return Dynamixel(self)
  47. baudrate: int = 57600
  48. protocol_version: float = 2.0
  49. device_name: str = "" # /dev/tty.usbserial-1120'
  50. dynamixel_id: int = 1
  51. def __init__(self, config: Config):
  52. """Initialize the Dynamixel servo connection.
  53. Args:
  54. config: Configuration object containing connection settings.
  55. """
  56. self.config = config
  57. self.connect()
  58. def connect(self):
  59. """Establish connection with the Dynamixel servo."""
  60. if self.config.device_name == "":
  61. for port_name in os.listdir("/dev"):
  62. if "ttyUSB" in port_name or "ttyACM" in port_name:
  63. self.config.device_name = "/dev/" + port_name
  64. print(f"using device {self.config.device_name}")
  65. self.portHandler = PortHandler(self.config.device_name)
  66. # self.portHandler.LA
  67. self.packetHandler = PacketHandler(self.config.protocol_version)
  68. if not self.portHandler.openPort():
  69. raise Exception(f"Failed to open port {self.config.device_name}")
  70. if not self.portHandler.setBaudRate(self.config.baudrate):
  71. raise Exception(f"failed to set baudrate to {self.config.baudrate}")
  72. # self.operating_mode = OperatingMode.UNKNOWN
  73. # self.torque_enabled = False
  74. # self._disable_torque()
  75. self.operating_modes = [None for _ in range(32)]
  76. self.torque_enabled = [None for _ in range(32)]
  77. return True
  78. def disconnect(self):
  79. """Close the connection with the Dynamixel servo."""
  80. self.portHandler.closePort()
  81. def set_goal_position(self, motor_id, goal_position):
  82. """Set the goal position for the specified servo.
  83. Args:
  84. motor_id: ID of the servo to control.
  85. goal_position: Target position value.
  86. """
  87. # if self.operating_modes[motor_id] is not OperatingMode.POSITION:
  88. # self._disable_torque(motor_id)
  89. # self.set_operating_mode(motor_id, OperatingMode.POSITION)
  90. # if not self.torque_enabled[motor_id]:
  91. # self._enable_torque(motor_id)
  92. # self._enable_torque(motor_id)
  93. dxl_comm_result, dxl_error = self.packetHandler.write4ByteTxRx(
  94. self.portHandler, motor_id, self.ADDR_GOAL_POSITION, goal_position,
  95. )
  96. # self._process_response(dxl_comm_result, dxl_error)
  97. # print(f'set position of motor {motor_id} to {goal_position}')
  98. def set_pwm_value(self, motor_id: int, pwm_value, tries=3):
  99. """Set the PWM value for the specified servo.
  100. Args:
  101. motor_id: ID of the servo to control.
  102. pwm_value: PWM value to set.
  103. tries: Number of attempts to set the value.
  104. """
  105. if self.operating_modes[motor_id] is not OperatingMode.PWM:
  106. self._disable_torque(motor_id)
  107. self.set_operating_mode(motor_id, OperatingMode.PWM)
  108. if not self.torque_enabled[motor_id]:
  109. self._enable_torque(motor_id)
  110. # print(f'enabling torque')
  111. dxl_comm_result, dxl_error = self.packetHandler.write2ByteTxRx(
  112. self.portHandler, motor_id, self.ADDR_GOAL_PWM, pwm_value,
  113. )
  114. # self._process_response(dxl_comm_result, dxl_error)
  115. # print(f'set pwm of motor {motor_id} to {pwm_value}')
  116. if dxl_comm_result != COMM_SUCCESS:
  117. if tries <= 1:
  118. raise ConnectionError(
  119. f"dxl_comm_result: {self.packetHandler.getTxRxResult(dxl_comm_result)}",
  120. )
  121. print(
  122. f"dynamixel pwm setting failure trying again with {tries - 1} tries",
  123. )
  124. self.set_pwm_value(motor_id, pwm_value, tries=tries - 1)
  125. elif dxl_error != 0:
  126. print(f"dxl error {dxl_error}")
  127. raise ConnectionError(
  128. f"dynamixel error: {self.packetHandler.getTxRxResult(dxl_error)}",
  129. )
  130. def read_temperature(self, motor_id: int):
  131. """Read the temperature of the specified servo.
  132. Args:
  133. motor_id: ID of the servo to read from.
  134. Returns:
  135. The current temperature value.
  136. """
  137. return self._read_value(motor_id, ReadAttribute.TEMPERATURE, 1)
  138. def read_velocity(self, motor_id: int):
  139. """Read the current velocity of the specified servo.
  140. Args:
  141. motor_id: ID of the servo to read from.
  142. Returns:
  143. The current velocity value.
  144. """
  145. pos = self._read_value(motor_id, ReadAttribute.VELOCITY, 4)
  146. if pos > 2**31:
  147. pos -= 2**32
  148. # print(f'read position {pos} for motor {motor_id}')
  149. return pos
  150. def read_position(self, motor_id: int):
  151. """Read the current position of the specified servo.
  152. Args:
  153. motor_id: ID of the servo to read from.
  154. Returns:
  155. The current position value.
  156. """
  157. pos = self._read_value(motor_id, ReadAttribute.POSITION, 4)
  158. if pos > 2**31:
  159. pos -= 2**32
  160. # print(f'read position {pos} for motor {motor_id}')
  161. return pos
  162. def read_position_degrees(self, motor_id: int) -> float:
  163. """Read the current position of the specified servo in degrees.
  164. Args:
  165. motor_id: ID of the servo to read from.
  166. Returns:
  167. The current position in degrees.
  168. """
  169. return (self.read_position(motor_id) / 4096) * 360
  170. def read_position_radians(self, motor_id: int) -> float:
  171. """Read the current position of the specified servo in radians.
  172. Args:
  173. motor_id: ID of the servo to read from.
  174. Returns:
  175. The current position in radians.
  176. """
  177. return (self.read_position(motor_id) / 4096) * 2 * math.pi
  178. def read_current(self, motor_id: int):
  179. """Read the current value of the specified servo.
  180. Args:
  181. motor_id: ID of the servo to read from.
  182. Returns:
  183. The current value.
  184. """
  185. current = self._read_value(motor_id, ReadAttribute.CURRENT, 2)
  186. if current > 2**15:
  187. current -= 2**16
  188. return current
  189. def read_present_pwm(self, motor_id: int):
  190. """Read the current PWM value of the specified servo.
  191. Args:
  192. motor_id: ID of the servo to read from.
  193. Returns:
  194. The current PWM value.
  195. """
  196. return self._read_value(motor_id, ReadAttribute.PWM, 2)
  197. def read_hardware_error_status(self, motor_id: int):
  198. """Read the hardware error status of the specified servo.
  199. Args:
  200. motor_id: ID of the servo to read from.
  201. Returns:
  202. The hardware error status value.
  203. """
  204. return self._read_value(motor_id, ReadAttribute.HARDWARE_ERROR_STATUS, 1)
  205. def set_id(self, old_id, new_id, use_broadcast_id: bool = False):
  206. """Set the ID of the Dynamixel servo.
  207. Args:
  208. old_id: Current ID of the servo.
  209. new_id: New ID to set.
  210. use_broadcast_id: If True, set IDs of all connected servos.
  211. If False, change only servo with self.config.id
  212. """
  213. if use_broadcast_id:
  214. current_id = 254
  215. else:
  216. current_id = old_id
  217. dxl_comm_result, dxl_error = self.packetHandler.write1ByteTxRx(
  218. self.portHandler, current_id, self.ADDR_ID, new_id,
  219. )
  220. self._process_response(dxl_comm_result, dxl_error, old_id)
  221. self.config.id = id
  222. def _enable_torque(self, motor_id):
  223. """Enable torque for the specified servo.
  224. Args:
  225. motor_id: ID of the servo to control.
  226. """
  227. dxl_comm_result, dxl_error = self.packetHandler.write1ByteTxRx(
  228. self.portHandler, motor_id, self.ADDR_TORQUE_ENABLE, 1,
  229. )
  230. self._process_response(dxl_comm_result, dxl_error, motor_id)
  231. self.torque_enabled[motor_id] = True
  232. def _disable_torque(self, motor_id):
  233. """Disable torque for the specified servo.
  234. Args:
  235. motor_id: ID of the servo to control.
  236. """
  237. dxl_comm_result, dxl_error = self.packetHandler.write1ByteTxRx(
  238. self.portHandler, motor_id, self.ADDR_TORQUE_ENABLE, 0,
  239. )
  240. self._process_response(dxl_comm_result, dxl_error, motor_id)
  241. self.torque_enabled[motor_id] = False
  242. def _process_response(self, dxl_comm_result: int, dxl_error: int, motor_id: int):
  243. """Process the response from a servo communication.
  244. Args:
  245. dxl_comm_result: Communication result.
  246. dxl_error: Error value.
  247. motor_id: ID of the servo that was communicated with.
  248. Raises:
  249. ConnectionError: If communication failed.
  250. RuntimeError: If servo reported an error.
  251. """
  252. if dxl_comm_result != COMM_SUCCESS:
  253. raise ConnectionError(
  254. f"dxl_comm_result for motor {motor_id}: {self.packetHandler.getTxRxResult(dxl_comm_result)}",
  255. )
  256. if dxl_error != 0:
  257. print(f"dxl error {dxl_error}")
  258. raise ConnectionError(
  259. f"dynamixel error for motor {motor_id}: {self.packetHandler.getTxRxResult(dxl_error)}",
  260. )
  261. def set_operating_mode(self, motor_id: int, operating_mode: OperatingMode):
  262. """Set the operating mode for the specified servo.
  263. Args:
  264. motor_id: ID of the servo to control.
  265. operating_mode: Operating mode to set.
  266. """
  267. dxl_comm_result, dxl_error = self.packetHandler.write2ByteTxRx(
  268. self.portHandler, motor_id, self.OPERATING_MODE_ADDR, operating_mode.value,
  269. )
  270. self._process_response(dxl_comm_result, dxl_error, motor_id)
  271. self.operating_modes[motor_id] = operating_mode
  272. def set_pwm_limit(self, motor_id: int, limit: int):
  273. """Set the PWM limit for the specified servo.
  274. Args:
  275. motor_id: ID of the servo to control.
  276. limit: PWM limit value to set.
  277. """
  278. dxl_comm_result, dxl_error = self.packetHandler.write2ByteTxRx(
  279. self.portHandler, motor_id, 36, limit,
  280. )
  281. self._process_response(dxl_comm_result, dxl_error, motor_id)
  282. def set_velocity_limit(self, motor_id: int, velocity_limit):
  283. """Set the velocity limit for the specified servo.
  284. Args:
  285. motor_id: ID of the servo to control.
  286. velocity_limit: Velocity limit value to set.
  287. """
  288. dxl_comm_result, dxl_error = self.packetHandler.write4ByteTxRx(
  289. self.portHandler, motor_id, self.ADDR_VELOCITY_LIMIT, velocity_limit,
  290. )
  291. self._process_response(dxl_comm_result, dxl_error, motor_id)
  292. def set_P(self, motor_id: int, P: int):
  293. """Set the position P gain for the specified servo.
  294. Args:
  295. motor_id: ID of the servo to control.
  296. P: Position P gain value to set.
  297. """
  298. dxl_comm_result, dxl_error = self.packetHandler.write2ByteTxRx(
  299. self.portHandler, motor_id, self.POSITION_P, P,
  300. )
  301. self._process_response(dxl_comm_result, dxl_error, motor_id)
  302. def set_I(self, motor_id: int, I: int):
  303. """Set the position I gain for the specified servo.
  304. Args:
  305. motor_id: ID of the servo to control.
  306. I: Position I gain value to set.
  307. """
  308. dxl_comm_result, dxl_error = self.packetHandler.write2ByteTxRx(
  309. self.portHandler, motor_id, self.POSITION_I, I,
  310. )
  311. self._process_response(dxl_comm_result, dxl_error, motor_id)
  312. def read_home_offset(self, motor_id: int):
  313. """Read the home offset of the specified servo.
  314. Args:
  315. motor_id: ID of the servo to read from.
  316. Returns:
  317. The home offset value.
  318. """
  319. self._disable_torque(motor_id)
  320. # dxl_comm_result, dxl_error = self.packetHandler.write4ByteTxRx(self.portHandler, motor_id,
  321. # ReadAttribute.HOMING_OFFSET.value, home_position)
  322. home_offset = self._read_value(motor_id, ReadAttribute.HOMING_OFFSET, 4)
  323. # self._process_response(dxl_comm_result, dxl_error)
  324. self._enable_torque(motor_id)
  325. return home_offset
  326. def set_home_offset(self, motor_id: int, home_position: int):
  327. """Set the home offset for the specified servo.
  328. Args:
  329. motor_id: ID of the servo to control.
  330. home_position: Home position value to set.
  331. """
  332. self._disable_torque(motor_id)
  333. dxl_comm_result, dxl_error = self.packetHandler.write4ByteTxRx(
  334. self.portHandler, motor_id, ReadAttribute.HOMING_OFFSET.value, home_position,
  335. )
  336. self._process_response(dxl_comm_result, dxl_error, motor_id)
  337. self._enable_torque(motor_id)
  338. def set_baudrate(self, motor_id: int, baudrate):
  339. """Set the baudrate for the specified servo.
  340. Args:
  341. motor_id: ID of the servo to control.
  342. baudrate: Baudrate value to set.
  343. """
  344. # translate baudrate into dynamixel baudrate setting id
  345. if baudrate == 57600:
  346. baudrate_id = 1
  347. elif baudrate == 1_000_000:
  348. baudrate_id = 3
  349. elif baudrate == 2_000_000:
  350. baudrate_id = 4
  351. elif baudrate == 3_000_000:
  352. baudrate_id = 5
  353. elif baudrate == 4_000_000:
  354. baudrate_id = 6
  355. else:
  356. raise Exception("baudrate not implemented")
  357. self._disable_torque(motor_id)
  358. dxl_comm_result, dxl_error = self.packetHandler.write1ByteTxRx(
  359. self.portHandler, motor_id, ReadAttribute.BAUDRATE.value, baudrate_id,
  360. )
  361. self._process_response(dxl_comm_result, dxl_error, motor_id)
  362. def _read_value(self, motor_id, attribute: ReadAttribute, num_bytes: int, tries=10):
  363. """Read a value from the specified servo address.
  364. Args:
  365. motor_id: ID of the servo to read from.
  366. attribute: Attribute to read.
  367. num_bytes: Number of bytes to read.
  368. tries: Number of attempts to read the value.
  369. Returns:
  370. The read value.
  371. """
  372. try:
  373. if num_bytes == 1:
  374. value, dxl_comm_result, dxl_error = self.packetHandler.read1ByteTxRx(
  375. self.portHandler, motor_id, attribute.value,
  376. )
  377. elif num_bytes == 2:
  378. value, dxl_comm_result, dxl_error = self.packetHandler.read2ByteTxRx(
  379. self.portHandler, motor_id, attribute.value,
  380. )
  381. elif num_bytes == 4:
  382. value, dxl_comm_result, dxl_error = self.packetHandler.read4ByteTxRx(
  383. self.portHandler, motor_id, attribute.value,
  384. )
  385. except Exception:
  386. if tries == 0:
  387. raise Exception
  388. return self._read_value(motor_id, attribute, num_bytes, tries=tries - 1)
  389. if dxl_comm_result != COMM_SUCCESS:
  390. if tries <= 1:
  391. # print("%s" % self.packetHandler.getTxRxResult(dxl_comm_result))
  392. raise ConnectionError(
  393. f"dxl_comm_result {dxl_comm_result} for servo {motor_id} value {value}",
  394. )
  395. print(
  396. f"dynamixel read failure for servo {motor_id} trying again with {tries - 1} tries",
  397. )
  398. time.sleep(0.02)
  399. return self._read_value(motor_id, attribute, num_bytes, tries=tries - 1)
  400. if (
  401. dxl_error != 0
  402. ): # # print("%s" % self.packetHandler.getRxPacketError(dxl_error))
  403. # raise ConnectionError(f'dxl_error {dxl_error} binary ' + "{0:b}".format(37))
  404. if tries == 0 and dxl_error != 128:
  405. raise Exception(
  406. f"Failed to read value from motor {motor_id} error is {dxl_error}",
  407. )
  408. return self._read_value(motor_id, attribute, num_bytes, tries=tries - 1)
  409. return value
  410. def set_home_position(self, motor_id: int):
  411. """Set the home position for the specified servo.
  412. Args:
  413. motor_id: ID of the servo to control.
  414. """
  415. print(f"setting home position for motor {motor_id}")
  416. self.set_home_offset(motor_id, 0)
  417. current_position = self.read_position(motor_id)
  418. print(f"position before {current_position}")
  419. self.set_home_offset(motor_id, -current_position)
  420. # dynamixel.set_home_offset(motor_id, -4096)
  421. # dynamixel.set_home_offset(motor_id, -4294964109)
  422. current_position = self.read_position(motor_id)
  423. # print(f'signed position {current_position - 2** 32}')
  424. print(f"position after {current_position}")