Figured out how to symbolically refer to PointCloud2 datatypes. (#348)

master
Holger Rapp 2017-05-19 17:23:09 +02:00 committed by GitHub
parent b9ad9bb4b8
commit 90381f7f2a
1 changed files with 3 additions and 3 deletions

View File

@ -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;