123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162 |
- import rospy
- import numpy as np
- import open3d as o3d
- from scipy.spatial.transform import Rotation as R
- import os
- from sensor_msgs.msg import PointCloud2
- from sensor_msgs.msg import PointField
- folder_path = rospy.get_param("folder_path")
- file_path = os.path.join(folder_path, 'pointcloud.txt')
- file_path_points = os.path.join(folder_path, 'points.txt')
- def cull_pointcloud(data,culling_radius):
- data_retained,data_culled = [],[]
- for i in range(data.shape[0]):
- for j in range(len(vectors)):
- A = start_points[j] - culling_radius * (vectors[j] / np.linalg.norm(vectors[j]))
- B = end_points[j] + culling_radius * (vectors[j] / np.linalg.norm(vectors[j]))
- aaa = (np.linalg.norm(data[i] - A) + np.linalg.norm(data[i] - B)) <= (2 * culling_radius + np.linalg.norm(B - A))
- distance = np.linalg.norm(np.cross(vectors[j], data[i]-start_points[j])) / np.linalg.norm(vectors[j])
-
- if distance <= culling_radius and aaa:
-
- data_culled.append(data[i])
- break
-
- elif j == len(vectors)-1:
- data_retained.append(data[i])
- data_retained = np.array(data_retained)
- data_culled = np.array(data_culled)
- return data_retained,data_culled
- def read_and_calculate_vectors(file_path):
- with open(file_path, 'r') as file:
-
- lines = file.readlines()
- start_points,end_points,vectors = [],[],[]
- for line in lines:
-
- points_str = line.strip().split('/')
-
-
- if len(points_str) == 2:
- point1_str = points_str[0].split(',')
- point2_str = points_str[1].split(',')
-
-
- point1 = [float(coord) for coord in point1_str]
- point2 = [float(coord) for coord in point2_str]
- start_points.append(point1)
- end_points.append(point2)
-
- vector = [p2 - p1 for p1, p2 in zip(point1, point2)]
-
- vectors.append(vector)
-
- return start_points,end_points,vectors
- def load_point_cloud_from_binary_txt(file_path):
- with open(file_path, 'rb') as f:
- binary_data = f.read()
-
- point_cloud = np.frombuffer(binary_data, dtype=np.float64).reshape(-1, 3)
-
- point_cloud = np.copy(point_cloud)
- return point_cloud
- pcd = o3d.geometry.PointCloud()
- pcd.points = o3d.utility.Vector3dVector(load_point_cloud_from_binary_txt(file_path))
- start_points,end_points,vectors = np.array(read_and_calculate_vectors(file_path_points))
- data = np.asarray(pcd.points)
- data_scaled2 = np.array(data) / 1000
- ptCloud_scaled1 = o3d.geometry.PointCloud()
- ptCloud_scaled2 = o3d.geometry.PointCloud()
- ptCloud_scaled2.points = o3d.utility.Vector3dVector(data_scaled2)
- def build_pointcloud2_msg(points):
- msg = PointCloud2()
- msg.header.stamp = rospy.Time(0)
- msg.header.frame_id = "world"
- if len(points.shape) == 3:
- msg.height = points.shape[1]
- msg.width = points.shape[0]
- else:
- msg.height = 1
- msg.width = len(points)
- msg.fields = [
- PointField('x', 0, PointField.FLOAT32, 1),
- PointField('y', 4, PointField.FLOAT32, 1),
- PointField('z', 8, PointField.FLOAT32, 1)]
- msg.is_bigendian = False
- msg.point_step = 12
- msg.row_step = msg.point_step * points.shape[0]
- msg.is_dense = False
- msg.data = np.asarray(points, np.float32).tobytes()
- return msg
- def talker():
- pub1 = rospy.Publisher("/pointcloud/output", PointCloud2, queue_size=10)
-
- rospy.init_node('publish_pointcloud', anonymous=True)
- rate = rospy.Rate(10)
-
- points1 = np.asarray(ptCloud_scaled1.points)
- points2 = np.asarray(ptCloud_scaled2.points)
-
- msg2 = build_pointcloud2_msg(points2)
-
- while not rospy.is_shutdown():
-
- sign_pointcloud = str(rospy.get_param("sign_pointcloud"))
- if sign_pointcloud == "1":
- rospy.set_param("sign_pointcloud",0)
- break
- pub1.publish(msg2)
-
-
- rate.sleep()
- if __name__ == '__main__':
- talker()
|