Closed fwarmuth closed 4 hours ago
Hi @fwarmuth. Thanks for testing the ROS2 preview.
I believe in ROS1 that rgba field had to be FLOAT32 for some technical reason. But this probably isn't the case anymore in ROS2. Could you check with the following change if it works as you expect? I tested it via rviz and it seems to work fine.
diff --git a/zivid_camera/src/zivid_camera.cpp b/zivid_camera/src/zivid_camera.cpp
index 300d125..0a4673c 100644
--- a/zivid_camera/src/zivid_camera.cpp
+++ b/zivid_camera/src/zivid_camera.cpp
@@ -737,7 +737,7 @@ void ZividCamera::publishPointCloudXYZRGBA(
msg->fields.push_back(createPointField("x", 0, sensor_msgs::msg::PointField::FLOAT32, 1));
msg->fields.push_back(createPointField("y", 4, sensor_msgs::msg::PointField::FLOAT32, 1));
msg->fields.push_back(createPointField("z", 8, sensor_msgs::msg::PointField::FLOAT32, 1));
- msg->fields.push_back(createPointField("rgba", 12, sensor_msgs::msg::PointField::FLOAT32, 1));
+ msg->fields.push_back(createPointField("rgba", 12, sensor_msgs::msg::PointField::UINT32, 1));
msg->is_dense = false;
// Note that the "rgba" field is actually byte order "bgra" on little-endian systems. For this
Hey, thanks for the reply! I will test it asap, i guess this will be the solution.
cheers
Test!
now, the convention to PCL point cloud works without any custom data types.
I would say that would be nice to see in the next release, its more the "ros-way-of-life" to use uint32
.
Regards!
Hi @fwarmuth , we will include this fix in the ROS2 driver
Hey,
Thanks for releasing a ROS2 Driver variant, finally getting rid of the ROS1 bridge and lowering the complexity.
I noticed that I cannot use the "normal" approach to convert ROS2 point clouds to PCL point clouds. Here is a callback function:
This will fail due to the wrong type of the rgba field being FLOAT32. As implemented here.
The workaround is to tell PCL about a new datatype:
And use it similar to this:
Is this the intended way? Cheers