Python thingies
25개 이상의 토픽을 선택하실 수 없습니다. Topics must start with a letter or number, can include dashes ('-') and can be up to 35 characters long.

109 lines
4.1KB

  1. from geometry_msgs.msg import Point, Pose, Quaternion
  2. from hexapod_python.ik import leg_offsets
  3. standing_pose = {
  4. 'body': Pose(
  5. position = Point(x = 0.0, y = 0.0, z = 105.0 ),
  6. orientation = Quaternion(x = 0.0, y = 0.0, z = 0.0, w = 1.0)
  7. ),
  8. 'legs': {
  9. 'e1': Point(x = leg_offsets['e1'].x + -100.0, y = leg_offsets['e1'].y, z = 0.0),
  10. 'e2': Point(x = leg_offsets['e2'].x + -100.0, y = leg_offsets['e2'].y, z = 0.0),
  11. 'e3': Point(x = leg_offsets['e3'].x + -100.0, y = leg_offsets['e3'].y, z = 0.0),
  12. 'e4': Point(x = leg_offsets['e4'].x + 100.0, y = leg_offsets['e4'].y, z = 0.0),
  13. 'e5': Point(x = leg_offsets['e5'].x + 100.0, y = leg_offsets['e5'].y, z = 0.0),
  14. 'e6': Point(x = leg_offsets['e6'].x + 100.0, y = leg_offsets['e6'].y, z = 0.0)
  15. }
  16. }
  17. stand_up_pose = {
  18. 'body': Pose(
  19. position = Point(x = 0.0, y = 0.0, z = 105.0 ),
  20. orientation = Quaternion(x = 0.0, y = 0.0, z = 0.0, w = 1.0)
  21. ),
  22. 'legs': {
  23. 'e1': Point(x = leg_offsets['e1'].x + -140.0, y = leg_offsets['e1'].y, z = 0.0),
  24. 'e2': Point(x = leg_offsets['e2'].x + -140.0, y = leg_offsets['e2'].y, z = 0.0),
  25. 'e3': Point(x = leg_offsets['e3'].x + -140.0, y = leg_offsets['e3'].y, z = 0.0),
  26. 'e4': Point(x = leg_offsets['e4'].x + 140.0, y = leg_offsets['e4'].y, z = 0.0),
  27. 'e5': Point(x = leg_offsets['e5'].x + 140.0, y = leg_offsets['e5'].y, z = 0.0),
  28. 'e6': Point(x = leg_offsets['e6'].x + 140.0, y = leg_offsets['e6'].y, z = 0.0)
  29. }
  30. }
  31. shutdown_pose = {
  32. 'body': Pose(
  33. position = Point(x = 0.0, y = 0.0, z = -5.0 ),
  34. orientation = Quaternion(x = 0.0, y = 0.0, z = 0.0, w = 1.0)
  35. ),
  36. 'legs': {
  37. 'e1': Point(x = leg_offsets['e1'].x + -140.0, y = leg_offsets['e1'].y, z = 0.0),
  38. 'e2': Point(x = leg_offsets['e2'].x + -140.0, y = leg_offsets['e2'].y, z = 0.0),
  39. 'e3': Point(x = leg_offsets['e3'].x + -140.0, y = leg_offsets['e3'].y, z = 0.0),
  40. 'e4': Point(x = leg_offsets['e4'].x + 140.0, y = leg_offsets['e4'].y, z = 0.0),
  41. 'e5': Point(x = leg_offsets['e5'].x + 140.0, y = leg_offsets['e5'].y, z = 0.0),
  42. 'e6': Point(x = leg_offsets['e6'].x + 140.0, y = leg_offsets['e6'].y, z = 0.0),
  43. }
  44. }
  45. calibration_pose = {
  46. 'body': Pose(
  47. position = Point(x = 0.0, y = 0.0, z = 0.0 ),
  48. orientation = Quaternion(x = 0.0, y = 0.0, z = 0.0, w = 1.0)
  49. ),
  50. 'legs': {
  51. 'e1': Point(x = -200.0, y = 150.0, z = 0.0),
  52. 'e2': Point(x = -200.0, y = 0.0, z = 0.0),
  53. 'e3': Point(x = -200.0, y = -150.0, z = 0.0),
  54. 'e4': Point(x = 200.0, y = -150.0, z = 0.0),
  55. 'e5': Point(x = 200.0, y = 0.0, z = 0.0),
  56. 'e6': Point(x = 200.0, y = 150.0, z = 0.0),
  57. }
  58. }
  59. def interpolate_pose(start, end, steps):
  60. body_step_x = (end['body'].position.x - start['body'].position.x) / (steps-1)
  61. body_step_y = (end['body'].position.y - start['body'].position.y) / (steps-1)
  62. body_step_z = (end['body'].position.z - start['body'].position.z) / (steps-1)
  63. leg_step_x = {}
  64. leg_step_y = {}
  65. leg_step_z = {}
  66. for leg in start['legs']:
  67. leg_step_x[leg] = (end['legs'][leg].x - start['legs'][leg].x) / (steps-1)
  68. leg_step_y[leg] = (end['legs'][leg].y - start['legs'][leg].y) / (steps-1)
  69. leg_step_z[leg] = (end['legs'][leg].z - start['legs'][leg].z) / (steps-1)
  70. poses = []
  71. for i in range(0, steps):
  72. pose = {
  73. 'body': Pose(
  74. position = Point(
  75. x = start['body'].position.x + body_step_x * i,
  76. y = start['body'].position.y + body_step_y * i,
  77. z = start['body'].position.z + body_step_z * i
  78. ),
  79. orientation = Quaternion(x = 0.0, y = 0.0, z = 0.0, w = 1.0)
  80. ),
  81. 'legs': {}
  82. }
  83. for leg in start['legs']:
  84. pose['legs'][leg] = Point(
  85. x = start['legs'][leg].x + leg_step_x[leg] * i,
  86. y = start['legs'][leg].y + leg_step_y[leg] * i,
  87. z = start['legs'][leg].z + leg_step_z[leg] * i
  88. )
  89. poses.append(pose)
  90. return poses