check.py 6.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148
  1. import rospy, sys
  2. import numpy as np
  3. from tf.transformations import euler_from_quaternion,quaternion_from_euler,quaternion_from_euler, quaternion_multiply
  4. # def traj_validity_check(trajectory):
  5. # if type (trajectory)is moveit_msgs.msg._RobotTrajectory.RobotTrajectory:
  6. # point_num=len(trajectory.joint_trajectory.point)
  7. # trajectory.joint_trajectory.point.positions
  8. # # for i
  9. # trajectory.joint_trajectory.point.velocities
  10. # trajectory.joint_trajectory.point.accelerations
  11. # return 0
  12. # # else:
  13. # # raise MoveItCommanderException(
  14. # # "Expected value in the range from 0 to 1 for scaling factor"
  15. # # )
  16. # def scale_trajectory_speed(traj, scale):
  17. # # Create a new trajectory object
  18. # new_traj = RobotTrajectory()
  19. # # Initialize the new trajectory to be the same as the input trajectory
  20. # new_traj.joint_trajectory = traj.joint_trajectory
  21. # # Get the number of joints involved
  22. # n_joints = len(traj.joint_trajectory.joint_names)
  23. # # Get the number of points on the trajectory
  24. # n_points = len(traj.joint_trajectory.points)
  25. # # Store the trajectory points
  26. # points = list(traj.joint_trajectory.points)
  27. # # Cycle through all points and joints and scale the time from start,
  28. # # as well as joint speed and acceleration
  29. # for i in range(n_points):
  30. # point = JointTrajectoryPoint()
  31. # # The joint positions are not scaled so pull them out first
  32. # point.positions = list(traj.joint_trajectory.points[i].positions)
  33. # # Next, scale the time_from_start for this point
  34. # # point.time_from_start = traj.joint_trajectory.points[i].time_from_start / scale
  35. # # Get the joint velocities for this point
  36. # point.velocities = list(traj.joint_trajectory.points[i].velocities)
  37. # # Get the joint accelerations for this point
  38. # point.accelerations = list(traj.joint_trajectory.points[i].accelerations)
  39. # # Scale the velocity and acceleration for each joint at this point
  40. # for j in range(n_joints):
  41. # # if point.positions[j]
  42. # if has_velocity_limits:
  43. # if point.velocities[j] > joint_max_velocity[j]:
  44. # vel_exception_point
  45. # rospy.loginfo("velocities Test OK")
  46. # else:
  47. # raise MoveItCommanderException("Expected value in the range from 0 to 1 for scaling factor")
  48. # if has_acceleration_limits:
  49. # point.accelerations[j] = point.accelerations[j] * scale * scale
  50. # # Store the scaled trajectory point
  51. # points[i] = point
  52. # rospy.loginfo("velocities Check OK")
  53. # # Assign the modified points to the new trajectory
  54. # new_traj.joint_trajectory.points = points
  55. # # Return the new trajecotry
  56. # return new_traj
  57. # else:
  58. # print("traj type is not std")
  59. def check_joint_positions(joint_trajectory):
  60. is_limited = False
  61. Limit_margin = True
  62. percentage = 0
  63. for i in range(len(joint_trajectory.joint_trajectory.points) - 1):
  64. if not is_limited:
  65. joint_positions1 = joint_trajectory.joint_trajectory.points[i].positions
  66. joint_positions2 = joint_trajectory.joint_trajectory.points[i + 1].positions
  67. for j in range(len(joint_positions1)):
  68. position_diff = abs(joint_positions1[j] - joint_positions2[j])
  69. if position_diff > 6:
  70. rospy.loginfo("point{}-joint{}:{}".format(i,j+1,joint_positions1))
  71. new_start_point = list(joint_trajectory.joint_trajectory.points[0].positions)
  72. #关节限位值
  73. joint_limt =[[],[],[],[-3.314,3.314],[],[-3.838,3.838]]
  74. #检查关节限位余量
  75. # midpoint = (joint_limt[j][0] + joint_limt[j][1])/2
  76. # distance_to_midpoint = abs(joint_trajectory.joint_trajectory.points[0].positions[j]- midpoint)
  77. Limit_point = joint_positions1[j]
  78. distance_to_Limit_point = abs(joint_trajectory.joint_trajectory.points[0].positions[j]- Limit_point)
  79. Joint_range = abs(joint_limt[j][0] - joint_limt[j][1])
  80. margin = distance_to_Limit_point / Joint_range
  81. if margin > 0.4:
  82. Limit_margin = True
  83. else:
  84. Limit_margin = False
  85. rospy.loginfo("margin = {}".format(margin))
  86. # if joint_positions1[j]>0:
  87. # new_start_point[j] -= np.pi*2
  88. # else:
  89. # new_start_point[j] += np.pi*2
  90. # rospy.loginfo("new point{}:{}".format(i,new_start_point))
  91. percentage = i/len(joint_trajectory.joint_trajectory.points)
  92. is_limited = True
  93. break
  94. if position_diff > 3:
  95. rospy.loginfo("point{}-joint{}:{}".format(i,j+1,joint_positions1))
  96. Limit_margin = True
  97. is_limited = True
  98. break
  99. if is_limited:
  100. break
  101. if not is_limited:
  102. rospy.loginfo("joint positions check OK")
  103. return is_limited,Limit_margin
  104. def angle_adjustment(pose,axis,angle):
  105. if len(pose) == 6:
  106. q_initial = quaternion_from_euler(pose[3], pose[4], pose[5])
  107. else:
  108. q_initial = (pose[3], pose[4], pose[5],pose[6])
  109. if axis == 'z':
  110. q_rotation = quaternion_from_euler(0, 0, angle)
  111. if axis == 'y':
  112. q_rotation = quaternion_from_euler(0, angle, 0)
  113. if axis == 'x':
  114. q_rotation = quaternion_from_euler(angle, 0, 0)
  115. q_new = quaternion_multiply(q_initial, q_rotation)
  116. pose[3:] = q_new
  117. return pose