Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Update to open3d 0.9 w/ ROS Melodic #2

Closed
wants to merge 2 commits into from
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions .gitignore
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
conversion_result.pcd
14 changes: 7 additions & 7 deletions lib_cloud_conversion_between_Open3D_and_ROS.py
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,7 @@ def convertCloudFromRosToOpen3d(ros_cloud):
cloud_data = list(pc2.read_points(ros_cloud, skip_nans=True, field_names = field_names))

# Check empty
open3d_cloud = open3d.PointCloud()
open3d_cloud = open3d.geometry.PointCloud()
if len(cloud_data)==0:
print("Converting an empty cloud")
return None
Expand All @@ -96,11 +96,11 @@ def convertCloudFromRosToOpen3d(ros_cloud):
rgb = [convert_rgbUint32_to_tuple(rgb) for x,y,z,rgb in cloud_data ]

# combine
open3d_cloud.points = open3d.Vector3dVector(np.array(xyz))
open3d_cloud.colors = open3d.Vector3dVector(np.array(rgb)/255.0)
open3d_cloud.points = open3d.utility.Vector3dVector(np.array(xyz))
open3d_cloud.colors = open3d.utility.Vector3dVector(np.array(rgb)/255.0)
else:
xyz = [(x,y,z) for x,y,z in cloud_data ] # get xyz
open3d_cloud.points = open3d.Vector3dVector(np.array(xyz))
open3d_cloud.points = open3d.utility.Vector3dVector(np.array(xyz))

# return
return open3d_cloud
Expand All @@ -117,7 +117,7 @@ def convertCloudFromRosToOpen3d(ros_cloud):
else: # test XYZRGB point cloud format
filename=PYTHON_FILE_PATH+"test_cloud_XYZRGB.pcd"

open3d_cloud = open3d.read_point_cloud(filename)
open3d_cloud = open3d.io.read_point_cloud(filename)
rospy.loginfo("Loading cloud from file by open3d.read_point_cloud: ")
print(open3d_cloud)
print("")
Expand Down Expand Up @@ -164,9 +164,9 @@ def callback(ros_cloud):

# write to file
output_filename=PYTHON_FILE_PATH+"conversion_result.pcd"
open3d.write_point_cloud(output_filename, received_open3d_cloud)
open3d.io.write_point_cloud(output_filename, received_open3d_cloud)
rospy.loginfo("-- Write result point cloud to: "+output_filename)

# draw
open3d.draw_geometries([received_open3d_cloud])
open3d.visualization.draw_geometries([received_open3d_cloud])
rospy.loginfo("-- Finish display. The program is terminating ...\n")