62 #include <ros/package.h>
65 #include <pcl/point_cloud.h>
66 #include <pcl/point_types.h>
110 char szFileName[255] = {0};
111 sprintf(szFileName,
"/tmp/cloud_dump_%04d.csv", cnt);
113 fout = fopen(szFileName,
"w");
117 fprintf(fout,
"%-8s;%-8s;%-8s;%-8s;%-8s;%-8s\n",
"X(col)",
"Y(Col)",
"X",
"Y",
"Z",
"Range");
118 for (i = 0; i < cloud->height; i++)
120 for (j = 0; j < cloud->width; j++)
122 float xRange,yRange,zRange;
124 memcpy(&xRange, &(cloud->data[x_offset]),
sizeof(
float));
125 memcpy(&yRange, &(cloud->data[y_offset]),
sizeof(
float));
126 memcpy(&zRange, &(cloud->data[z_offset]),
sizeof(
float));
127 range = sqrt(xRange*xRange + yRange*yRange + zRange*zRange);
128 fprintf(fout,
"%5d;%5d;", i, j);
129 fprintf(fout,
"%8.3f;%8.3f;%8.3f;%8.3f", xRange, yRange, zRange, range);
132 x_offset += cloud->point_step;
133 y_offset += cloud->point_step;
134 z_offset += cloud->point_step;
163 int conversionTask = 3;
164 float range_eps = 0.1;
167 int heightUsed = cloud->
height;
176 for (
size_t d = 0;
d < cloud->fields.size(); ++
d)
178 if (cloud->fields[
d].name ==
"intensity")
180 rgb_index =
static_cast<int>(
d);
183 if (cloud->fields[
d].name ==
"x")
185 x_index =
static_cast<int>(
d);
188 if (cloud->fields[
d].name ==
"y")
190 y_index =
static_cast<int>(
d);
193 if (cloud->fields[
d].name ==
"z")
195 z_index =
static_cast<int>(
d);
208 throw std::runtime_error(
"No intensity entry!!");
214 int heightStretch = 5;
216 int imgChannelCnt = 0;
218 const int maxAllowedEncodings = 2;
219 bool encodeFlagArray[maxAllowedEncodings] = {0};
220 bool useHDFormat =
false;
221 if (conversionTask & 1)
223 encodeFlagArray[0] =
true;
226 if (conversionTask & 2)
228 encodeFlagArray[1] =
true;
232 if (cloud->width == 0 && heightUsed == 0)
234 throw std::runtime_error(
"Needs to be a dense like cloud!!");
238 msg.height = heightStretch * heightUsed * imgChannelCnt;
239 msg.width = cloud->width;
242 if (1080 >
msg.height)
246 if (1920 >
msg.width)
252 int rgb_offset = cloud->fields[rgb_index].offset;
253 int x_offset = cloud->fields[x_index].offset;
254 int y_offset = cloud->fields[y_index].offset;
255 int z_offset = cloud->fields[z_index].offset;
259 int point_step = cloud->point_step;
268 dump2csv(cloud, x_offset, y_offset, z_offset);
271 msg.encoding =
"bgr8";
272 msg.step =
static_cast<uint32_t
>(
msg.width *
sizeof(uint8_t) * 3);
276 int maxY = imgChannelCnt * heightStretch * heightUsed;
278 for (
size_t y = 0; y < heightUsed; y++)
280 for (
size_t x = 0; x < cloud->width; x++)
282 for (
int chIdx = 0; chIdx < imgChannelCnt; chIdx++)
286 for (
int j = 0; j < maxAllowedEncodings; j++)
288 if (encodeFlagArray[j])
290 if (chIdx == encodingCnt)
299 for (
int rowInner = 0; rowInner < heightStretch; rowInner++)
301 int rowTmp = (y * heightStretch + rowInner);
302 rowTmp += encodingCnt * heightStretch * heightUsed;
304 int rowInnerIdx = maxY - (rowTmp) - 1;
306 xTmp = cloud->width - 1 - x;
307 uint8_t *pixel = &(
msg.data[rowInnerIdx *
msg.step + xTmp * 3]);
308 uint8_t *pixelVGA =
NULL;
315 memcpy(&xRange, &(cloud->data[x_offset]),
sizeof(
float));
316 memcpy(&yRange, &(cloud->data[y_offset]),
sizeof(
float));
317 memcpy(&zRange, &(cloud->data[z_offset]),
sizeof(
float));
318 range = sqrt(xRange * xRange + yRange * yRange + zRange * zRange);
319 memcpy(&intensity, &(cloud->data[rgb_offset]),
sizeof(
float));
320 if (intensity > 255.0)
328 unsigned char r, g, b;
329 unsigned char grey = 0;
332 grey = (
unsigned char) intensity;
340 bool setBlack =
false;
341 if (range < range_eps)
345 if (range < minRealRange)
347 range = minRealRange;
350 if (range > maxRealRange)
352 range = maxRealRange;
358 grey = (
unsigned char) range;
384 rgb_offset += point_step;
385 x_offset += point_step;
386 y_offset += point_step;
387 z_offset += point_step;
399 printf(
"sick_pcl_converter <input_pointcloud2-topic> <output_image-topic>");
405 bool dumpCsvFlag =
false;
415 std::string inputTopic = argv[1];
416 std::string outputTopic = argv[2];
417 ros::init(argc, argv,
"sick_pcl_converter");
424 nh.
getParam(
"dump_csv", dumpCsvFlag);
430 ROS_INFO(
"Dump to csv file for debugging enabled.\n Files will be dumped at /tmp ");
435 if (heatMap.length() > 0)
437 std::string heatMapFileName = path +
"/config/" + heatMap;
441 ROS_INFO(
"Subscribing to %s and publishing images to %s\n", inputTopic.c_str(), outputTopic.c_str());