dycl_0506.py 5.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162
  1. #!/usr/bin/env python3
  2. import rospy
  3. import numpy as np
  4. import open3d as o3d
  5. from scipy.spatial.transform import Rotation as R
  6. import os
  7. from sensor_msgs.msg import PointCloud2
  8. from sensor_msgs.msg import PointField
  9. folder_path = rospy.get_param("folder_path")
  10. file_path = os.path.join(folder_path, 'pointcloud.txt')
  11. file_path_points = os.path.join(folder_path, 'points.txt')
  12. #chen############################################################################################
  13. def cull_pointcloud(data,culling_radius):
  14. data_retained,data_culled = [],[]
  15. for i in range(data.shape[0]): # 遍历每一个点 P
  16. for j in range(len(vectors)): # 遍历每一个向量 u
  17. A = start_points[j] - culling_radius * (vectors[j] / np.linalg.norm(vectors[j]))
  18. B = end_points[j] + culling_radius * (vectors[j] / np.linalg.norm(vectors[j]))
  19. aaa = (np.linalg.norm(data[i] - A) + np.linalg.norm(data[i] - B)) <= (2 * culling_radius + np.linalg.norm(B - A))
  20. distance = np.linalg.norm(np.cross(vectors[j], data[i]-start_points[j])) / np.linalg.norm(vectors[j])
  21. # 如果有任何一个距离小于等于10,则标记为不满足条件
  22. if distance <= culling_radius and aaa:
  23. # if aaa:
  24. data_culled.append(data[i])
  25. break
  26. # 如果该点对所有向量的距离都大于10,则保留该点
  27. elif j == len(vectors)-1:
  28. data_retained.append(data[i])
  29. data_retained = np.array(data_retained)
  30. data_culled = np.array(data_culled)
  31. return data_retained,data_culled
  32. ################################点云降采样################################
  33. # 从文件中读取焊缝起点和终点,并计算两点构成的向量
  34. def read_and_calculate_vectors(file_path):
  35. with open(file_path, 'r') as file:
  36. # 逐行读取文件内容
  37. lines = file.readlines()
  38. start_points,end_points,vectors = [],[],[]
  39. for line in lines:
  40. # 去除行尾的换行符并按'/'分割每一行
  41. points_str = line.strip().split('/')
  42. # 确保每一行都正确地分为两部分
  43. if len(points_str) == 2:
  44. point1_str = points_str[0].split(',')
  45. point2_str = points_str[1].split(',')
  46. # 转换字符串为浮点数列表,构造三维点
  47. point1 = [float(coord) for coord in point1_str]
  48. point2 = [float(coord) for coord in point2_str]
  49. start_points.append(point1)
  50. end_points.append(point2)
  51. # 计算向量:向量 = 点2 - 点1
  52. vector = [p2 - p1 for p1, p2 in zip(point1, point2)]
  53. vectors.append(vector)
  54. return start_points,end_points,vectors
  55. # 读取文件
  56. def load_point_cloud_from_binary_txt(file_path):
  57. with open(file_path, 'rb') as f:
  58. binary_data = f.read()
  59. # 将二进制数据转换为 NumPy 数组
  60. point_cloud = np.frombuffer(binary_data, dtype=np.float64).reshape(-1, 3)
  61. # 将数组转换为可写状态
  62. point_cloud = np.copy(point_cloud)
  63. return point_cloud
  64. pcd = o3d.geometry.PointCloud()
  65. pcd.points = o3d.utility.Vector3dVector(load_point_cloud_from_binary_txt(file_path))
  66. #pcd = pcd.voxel_down_sample(voxel_size = 4)
  67. ################################去掉焊缝周围的点云#################################
  68. # 计算焊缝向量
  69. start_points,end_points,vectors = np.array(read_and_calculate_vectors(file_path_points))
  70. data = np.asarray(pcd.points)
  71. # culling_radius2 = float(rospy.get_param('culling_radius'))
  72. # data_retained2,data_culled2 =cull_pointcloud(data,culling_radius2)
  73. # data_scaled2 = np.array(data_retained2) / 1000
  74. data_scaled2 = np.array(data) / 1000
  75. ptCloud_scaled1 = o3d.geometry.PointCloud()
  76. ptCloud_scaled2 = o3d.geometry.PointCloud()
  77. ptCloud_scaled2.points = o3d.utility.Vector3dVector(data_scaled2)
  78. #####################################################################################################################################################################
  79. def build_pointcloud2_msg(points):
  80. msg = PointCloud2()
  81. msg.header.stamp = rospy.Time(0)
  82. msg.header.frame_id = "world"
  83. if len(points.shape) == 3:
  84. msg.height = points.shape[1]
  85. msg.width = points.shape[0]
  86. else:
  87. msg.height = 1
  88. msg.width = len(points)
  89. msg.fields = [
  90. PointField('x', 0, PointField.FLOAT32, 1),
  91. PointField('y', 4, PointField.FLOAT32, 1),
  92. PointField('z', 8, PointField.FLOAT32, 1)]
  93. msg.is_bigendian = False
  94. msg.point_step = 12
  95. msg.row_step = msg.point_step * points.shape[0]
  96. msg.is_dense = False
  97. msg.data = np.asarray(points, np.float32).tobytes()
  98. return msg
  99. def talker():
  100. pub1 = rospy.Publisher("/pointcloud/output", PointCloud2, queue_size=10)
  101. # pub2 = rospy.Publisher("/pointcloud/output2", PointCloud2, queue_size=10)
  102. rospy.init_node('publish_pointcloud', anonymous=True)
  103. rate = rospy.Rate(10)
  104. points1 = np.asarray(ptCloud_scaled1.points)
  105. points2 = np.asarray(ptCloud_scaled2.points)
  106. # msg1 = build_pointcloud2_msg(points1)
  107. msg2 = build_pointcloud2_msg(points2)
  108. while not rospy.is_shutdown():
  109. #机械臂完毕,退出点云发布
  110. sign_pointcloud = str(rospy.get_param("sign_pointcloud"))
  111. if sign_pointcloud == "1":
  112. rospy.set_param("sign_pointcloud",0)
  113. break
  114. pub1.publish(msg2)
  115. # pub2.publish(msg2)
  116. # print("pointcloud has published,sign_pointcloud ={}".format(sign_pointcloud))
  117. rate.sleep()
  118. if __name__ == '__main__':
  119. talker()