You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
Although it seems that this repo is not maintained for a while, hopefully this is still helpful for ppl who wish to quickly find the solution to convert open3d pcd to ros pointcloud2 msg.
Fixes to make convertCloudFromOpen3dToRos works:
Tested on open3d 0.17.0, ros noetic
# The data structure of each point in ros PointCloud2: 16 bits = x + y + z + rgbFIELDS_XYZ= [
PointField(name='x', offset=0, datatype=PointField.FLOAT32, count=1),
PointField(name='y', offset=4, datatype=PointField.FLOAT32, count=1),
PointField(name='z', offset=8, datatype=PointField.FLOAT32, count=1),
]
FIELDS_XYZRGB=FIELDS_XYZ+ \
[PointField(name='rgb', offset=12, datatype=PointField.FLOAT32, count=1)]
# Bit operationsBIT_MOVE_16=2**16BIT_MOVE_8=2**8convert_rgbUint32_to_tuple=lambdargb_uint32: (
(rgb_uint32&0x00ff0000)>>16, (rgb_uint32&0x0000ff00)>>8, (rgb_uint32&0x000000ff)
)
convert_rgbFloat_to_tuple=lambdargb_float: convert_rgbUint32_to_tuple(
int(cast(pointer(c_float(rgb_float)), POINTER(c_uint32)).contents.value)
)
# Convert the datatype of point cloud from Open3D to ROS PointCloud2 (XYZRGB only)defconvertCloudFromOpen3dToRos(open3d_cloud, frame_id="map"):
# Set "header"header=Header()
header.stamp=rospy.Time.now()
header.frame_id=frame_id# Set "fields" and "cloud_data"points=np.asarray(open3d_cloud.points)
ifnotopen3d_cloud.colors: # XYZ onlyfields=FIELDS_XYZcloud_data=pointselse: # XYZ + RGBfields=FIELDS_XYZRGB# -- Change rgb color from "three float" to "one 24-byte int"# 0x00FFFFFF is white, 0x00000000 is black.colors=np.floor(np.asarray(open3d_cloud.colors)*255)
colors=colors.astype(np.uint32)
colors=colors[:,2] *BIT_MOVE_16+colors[:,1] *BIT_MOVE_8+colors[:,1]
colors=colors.view(np.float32)
cloud_data= [tuple((*p, c)) forp, cinzip(points, colors)]
# create ros_cloudreturnpc2.create_cloud(header, fields, cloud_data)
when viz on rviz, show it in RGB8
The text was updated successfully, but these errors were encountered:
Although it seems that this repo is not maintained for a while, hopefully this is still helpful for ppl who wish to quickly find the solution to convert open3d pcd to ros pointcloud2 msg.
Fixes to make
convertCloudFromOpen3dToRos
works:Tested on open3d
0.17.0
, rosnoetic
when viz on rviz, show it in
RGB8
The text was updated successfully, but these errors were encountered: