hanqiangpose.py 3.4 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586878889
  1. import numpy as np
  2. from scipy.spatial.transform import Rotation as R
  3. import open3d as o3d
  4. from scipy.spatial import KDTree
  5. import tf.transformations as tft
  6. import os
  7. import rospy
  8. from math import acos,tan,atan,degrees,sqrt,sin,cos
  9. def rpy2quaternion(roll, pitch, yaw):#zyx
  10. x=sin(roll/2)*cos(pitch/2)*cos(yaw/2)-cos(roll/2)*sin(pitch/2)*sin(yaw/2)
  11. y=cos(roll/2)*sin(pitch/2)*cos(yaw/2)+sin(roll/2)*cos(pitch/2)*sin(yaw/2)
  12. z=cos(roll/2)*cos(pitch/2)*sin(yaw/2)-sin(roll/2)*sin(pitch/2)*cos(yaw/2)
  13. w=cos(roll/2)*cos(pitch/2)*cos(yaw/2)+sin(roll/2)*sin(pitch/2)*sin(yaw/2)
  14. return [x, y, z, w]
  15. def get_hanfeng(file_path):
  16. """从文件中读取焊缝起点、终点和中间点,并计算两点构成的向量"""
  17. with open(file_path, 'r') as file:
  18. # 逐行读取文件内容
  19. lines = file.readlines()
  20. start_points, end_points, midpoints , hanfeng = [],[],[],[]
  21. for line in lines:
  22. # 去除行尾的换行符并按'/'分割每一行
  23. points_str = line.strip().split('/')
  24. # 确保每一行都正确地分为两部分
  25. if len(points_str) == 2:
  26. point1_str = points_str[0].split(',')
  27. point2_str = points_str[1].split(',')
  28. # 转换字符串为浮点数列表,构造三维点
  29. point1 = [float(coord) for coord in point1_str]
  30. point2 = [float(coord) for coord in point2_str]
  31. midpoint = [(p2 + p1)/2 for p1, p2 in zip(point1, point2)]
  32. vector = [p2 - p1 for p1, p2 in zip(point1, point2)]
  33. start_points.append(point1)
  34. end_points.append(point2)
  35. midpoints.append(midpoint)
  36. hanfeng.append(vector)
  37. return start_points, end_points, midpoints, hanfeng
  38. def calculate_angle_with_xy_plane(point1,point2):
  39. # 计算方向向量
  40. dir_vector = np.array([point2[0] - point1[0], point2[1] - point1[1], point2[2] - point1[2]])
  41. # 计算方向向量在 xy 平面上的投影
  42. proj_vector = np.array([point2[0] - point1[0], point2[1] - point1[1], 0])
  43. # 计算夹角
  44. angle = acos(np.dot(dir_vector, proj_vector) / (np.linalg.norm(dir_vector) * np.linalg.norm(proj_vector)))
  45. angle_deg = degrees(angle)
  46. return angle_deg
  47. def run():
  48. file_path = rospy.get_param("folder_path")
  49. file_path_points = os.path.join(file_path, 'points_guihua.txt')
  50. file_path_result = os.path.join(file_path, 'result.txt')
  51. result=[]
  52. start_points, end_points, midpoints, hanfeng = get_hanfeng(file_path_points)
  53. # 计算位姿
  54. for i in range(len(hanfeng)):
  55. if(calculate_angle_with_xy_plane(start_points[i], end_points[i])<45):#平缝
  56. q1 = rpy2quaternion(0,np.pi,0)
  57. q2 = rpy2quaternion(0,np.pi,0)
  58. result.append(("s", start_points[i], end_points[i], q1, q2))
  59. else:
  60. q1 = rpy2quaternion(0,np.pi,0)
  61. q2 = rpy2quaternion(0,np.pi,0)
  62. result.append(("s", start_points[i], end_points[i], q1, q2))
  63. # 打开文件准备写入
  64. with open(file_path_result, "w") as file:
  65. for group in result:
  66. # 对于每个数据组,将每个部分用逗号连接,然后在各部分间插入斜杠
  67. line = "/".join([",".join(map(str, sublist)) for sublist in group]) + "\n"
  68. file.write(line)
  69. rospy.loginfo("Welding Angle calculation completed")
  70. if __name__ == '__main__':
  71. run()