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.

main.py 4.1 kB

10 months ago
123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129
  1. """TODO: Add docstring."""
  2. import os
  3. import time
  4. import numpy as np
  5. from dora import Node
  6. from reachy_sdk import ReachySDK
  7. from reachy_sdk.trajectory import goto
  8. def r_arm_inverse_kinematics(reachy, pose, action) -> list:
  9. """TODO: Add docstring."""
  10. a = np.array(
  11. [
  12. [0, 0, -1, pose[0] + action[0]],
  13. [0, 1, 0, pose[1] + action[1]],
  14. [1, 0, 0, pose[2] + action[2]],
  15. [0, 0, 0, 1],
  16. ],
  17. )
  18. return reachy.r_arm.inverse_kinematics(a)
  19. def happy_antennas(reachy):
  20. """TODO: Add docstring."""
  21. reachy.head.l_antenna.speed_limit = 480.0
  22. reachy.head.r_antenna.speed_limit = 480.0
  23. for _ in range(1):
  24. reachy.head.l_antenna.goal_position = 10.0
  25. reachy.head.r_antenna.goal_position = -10.0
  26. time.sleep(0.1)
  27. reachy.head.l_antenna.goal_position = -10.0
  28. reachy.head.r_antenna.goal_position = 10.0
  29. time.sleep(0.1)
  30. reachy.head.l_antenna.goal_position = 0.0
  31. reachy.head.r_antenna.goal_position = 0.0
  32. def sad_antennas(reachy):
  33. """TODO: Add docstring."""
  34. reachy.head.l_antenna.speed_limit = 360.0
  35. reachy.head.r_antenna.speed_limit = 360.0
  36. reachy.head.l_antenna.goal_position = 140.0
  37. reachy.head.r_antenna.goal_position = -140.0
  38. def main():
  39. """TODO: Add docstring."""
  40. node = Node()
  41. robot_ip = os.getenv("ROBOT_IP", "10.42.0.24")
  42. reachy = ReachySDK(robot_ip, with_mobile_base=False)
  43. reachy.turn_on("r_arm")
  44. reachy.turn_on("head")
  45. r_arm_pose = [0.2, -0.46, -0.42]
  46. head_pose = [
  47. reachy.head.neck_roll.present_position,
  48. reachy.head.neck_yaw.present_position,
  49. reachy.head.neck_pitch.present_position,
  50. ]
  51. default_pose = r_arm_inverse_kinematics(reachy, r_arm_pose, [0, 0, 0])
  52. goto(
  53. {joint: pos for joint, pos in zip(reachy.r_arm.joints.values(), default_pose, strict=False)},
  54. duration=3,
  55. )
  56. for event in node:
  57. if event["type"] != "INPUT":
  58. continue
  59. if event["id"] == "r_arm_action":
  60. action = event["value"].to_pylist()
  61. joint_pose = r_arm_inverse_kinematics(reachy, r_arm_pose, action)
  62. goto(
  63. {
  64. joint: pos
  65. for joint, pos in zip(reachy.r_arm.joints.values(), joint_pose, strict=False)
  66. },
  67. duration=0.200,
  68. )
  69. r_arm_pose = np.array(r_arm_pose) + np.array(action)
  70. elif event["id"] == "head_action":
  71. action = event["value"].to_pylist()
  72. for i in range(5):
  73. head_pose = np.array(head_pose) + np.array(action) / 5
  74. reachy.head.neck_roll.goal_position = head_pose[0]
  75. reachy.head.neck_yaw.goal_position = head_pose[1]
  76. reachy.head.neck_pitch.goal_position = head_pose[2]
  77. time.sleep(0.03)
  78. elif event["id"] == "antenna_action":
  79. text = event["value"].to_pylist()[0]
  80. if text == "smile":
  81. happy_antennas(reachy)
  82. elif text == "cry":
  83. sad_antennas(reachy)
  84. elif event["id"] == "gripper_action":
  85. action = event["value"].to_pylist()[0]
  86. step = (action - reachy.joints.r_gripper.present_position) / 10
  87. goal = reachy.joints.r_gripper.present_position
  88. for i in range(10):
  89. goal += step
  90. goal = np.clip(goal, -100, 100)
  91. reachy.joints.r_gripper.goal_position = goal
  92. time.sleep(0.02)
  93. # When opening the gripper always go to default pose
  94. if action == -100:
  95. goto(
  96. {
  97. joint: pos
  98. for joint, pos in zip(
  99. reachy.r_arm.joints.values(), default_pose, strict=False,
  100. )
  101. },
  102. duration=3,
  103. )
  104. r_arm_pose = [0.2, -0.46, -0.42]
  105. reachy.turn_off_smoothly("r_arm")
  106. reachy.turn_off_smoothly("head")