check.py 6.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145
  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. #####检查关节限位#####
  5. def check_joint_positions(joint_trajectory):
  6. is_limited = False #初始化为满足限制条件
  7. Limit_margin = True #限制边界,初始化为True,用来检查是否超出限制条件
  8. for i in range(len(joint_trajectory.joint_trajectory.points) - 1): #遍历除了最后一个关节轨迹点其他所有轨迹点
  9. if not is_limited:
  10. joint_positions1 = joint_trajectory.joint_trajectory.points[i].positions #选择两个相邻的关节轨迹点
  11. joint_positions2 = joint_trajectory.joint_trajectory.points[i + 1].positions
  12. for j in range(len(joint_positions1)): #遍历但前轨迹点的每个关节点,这里是joint_positions1
  13. position_diff = abs(joint_positions1[j] - joint_positions2[j]) #计算相邻关节轨迹点的关节点绝对差值,归一化到[-pi,pi]
  14. if position_diff > 6: #限位阈值,6rad=343.8度
  15. rospy.loginfo("发生大角度翻转: point{}-joint{}:{}".format(i,j+1,joint_positions1))
  16. #关节限位值
  17. joint_limt =[[],[],[],[-1.6,1.6],[],[-3.838,3.838]]
  18. #设定限位点为当前关节点
  19. Limit_point = joint_positions1[j]
  20. #计算限位点(当前点)与起点位置的偏移量的绝对值
  21. distance_to_Limit_point = abs(joint_trajectory.joint_trajectory.points[0].positions[j]- Limit_point)
  22. Joint_range = abs(joint_limt[j][0] - joint_limt[j][1]) #计算关节限位范围
  23. margin = distance_to_Limit_point / Joint_range #计算限位余量:偏移量的绝对值/关节限位范围
  24. if margin > 0.3:
  25. Limit_margin = True
  26. else:
  27. Limit_margin = False
  28. rospy.loginfo("margin = {}".format(margin))
  29. is_limited = True
  30. break
  31. if position_diff > 3: #限位阈值,3rad=171.9度
  32. rospy.loginfo("point{}-joint{}:{}".format(i,j+1,joint_positions1))
  33. Limit_margin = True
  34. is_limited = True
  35. break
  36. if is_limited:
  37. break
  38. if not is_limited:
  39. rospy.loginfo("Check OK! 轨迹有效")
  40. return is_limited,Limit_margin
  41. #姿态调整
  42. def angle_adjustment(pose,axis,angle):
  43. if len(pose) == 6:
  44. q_initial = quaternion_from_euler(pose[3], pose[4], pose[5]) #初始姿态四元数,将欧拉角转换为四元数
  45. else:
  46. q_initial = (pose[3], pose[4], pose[5],pose[6]) #len>6,默认为四元数
  47. if axis == 'z':
  48. q_rotation = quaternion_from_euler(0, 0, angle) #绕z轴旋转,转换得到关于z轴的旋转四元数
  49. if axis == 'y':
  50. q_rotation = quaternion_from_euler(0, angle, 0)
  51. if axis == 'x':
  52. q_rotation = quaternion_from_euler(angle, 0, 0)
  53. q_new = quaternion_multiply(q_initial, q_rotation) #q_new为调整后的姿态四元数,值初始姿态四元数乘以旋转四元数
  54. pose[3:] = q_new #将q_new放入pose列表中的3号索引以后的位置
  55. return pose
  56. # def traj_validity_check(trajectory):
  57. # if type (trajectory)is moveit_msgs.msg._RobotTrajectory.RobotTrajectory:
  58. # point_num=len(trajectory.joint_trajectory.point)
  59. # trajectory.joint_trajectory.point.positions
  60. # # for i
  61. # trajectory.joint_trajectory.point.velocities
  62. # trajectory.joint_trajectory.point.accelerations
  63. # return 0
  64. # # else:
  65. # # raise MoveItCommanderException(
  66. # # "Expected value in the range from 0 to 1 for scaling factor"
  67. # # )
  68. # def scale_trajectory_speed(traj, scale):
  69. # # Create a new trajectory object
  70. # new_traj = RobotTrajectory()
  71. # # Initialize the new trajectory to be the same as the input trajectory
  72. # new_traj.joint_trajectory = traj.joint_trajectory
  73. # # Get the number of joints involved
  74. # n_joints = len(traj.joint_trajectory.joint_names)
  75. # # Get the number of points on the trajectory
  76. # n_points = len(traj.joint_trajectory.points)
  77. # # Store the trajectory points
  78. # points = list(traj.joint_trajectory.points)
  79. # # Cycle through all points and joints and scale the time from start,
  80. # # as well as joint speed and acceleration
  81. # for i in range(n_points):
  82. # point = JointTrajectoryPoint()
  83. # # The joint positions are not scaled so pull them out first
  84. # point.positions = list(traj.joint_trajectory.points[i].positions)
  85. # # Next, scale the time_from_start for this point
  86. # # point.time_from_start = traj.joint_trajectory.points[i].time_from_start / scale
  87. # # Get the joint velocities for this point
  88. # point.velocities = list(traj.joint_trajectory.points[i].velocities)
  89. # # Get the joint accelerations for this point
  90. # point.accelerations = list(traj.joint_trajectory.points[i].accelerations)
  91. # # Scale the velocity and acceleration for each joint at this point
  92. # for j in range(n_joints):
  93. # # if point.positions[j]
  94. # if has_velocity_limits:
  95. # if point.velocities[j] > joint_max_velocity[j]:
  96. # vel_exception_point
  97. # rospy.loginfo("velocities Test OK")
  98. # else:
  99. # raise MoveItCommanderException("Expected value in the range from 0 to 1 for scaling factor")
  100. # if has_acceleration_limits:
  101. # point.accelerations[j] = point.accelerations[j] * scale * scale
  102. # # Store the scaled trajectory point
  103. # points[i] = point
  104. # rospy.loginfo("velocities Check OK")
  105. # # Assign the modified points to the new trajectory
  106. # new_traj.joint_trajectory.points = points
  107. # # Return the new trajecotry
  108. # return new_traj
  109. # else:
  110. # print("traj type is not std")