From 90381f7f2ac022fba3d38eae34004a1c51f5c450 Mon Sep 17 00:00:00 2001 From: Holger Rapp Date: Fri, 19 May 2017 17:23:09 +0200 Subject: [PATCH] Figured out how to symbolically refer to PointCloud2 datatypes. (#348) --- cartographer_ros/cartographer_ros/msg_conversion.cc | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/cartographer_ros/cartographer_ros/msg_conversion.cc b/cartographer_ros/cartographer_ros/msg_conversion.cc index a7aacd1..7720e5a 100644 --- a/cartographer_ros/cartographer_ros/msg_conversion.cc +++ b/cartographer_ros/cartographer_ros/msg_conversion.cc @@ -58,15 +58,15 @@ sensor_msgs::PointCloud2 PreparePointCloud2Message(const int64 timestamp, msg.fields.resize(3); msg.fields[0].name = "x"; msg.fields[0].offset = 0; - msg.fields[0].datatype = 7; + msg.fields[0].datatype = sensor_msgs::PointField::FLOAT32; msg.fields[0].count = 1; msg.fields[1].name = "y"; msg.fields[1].offset = 4; - msg.fields[1].datatype = 7; + msg.fields[1].datatype = sensor_msgs::PointField::FLOAT32; msg.fields[1].count = 1; msg.fields[2].name = "z"; msg.fields[2].offset = 8; - msg.fields[2].datatype = 7; + msg.fields[2].datatype = sensor_msgs::PointField::FLOAT32; msg.fields[2].count = 1; msg.is_bigendian = false; msg.point_step = 16;