48 #include <sensor_msgs/PointCloud2.h> 
   50 #include <pcl/point_cloud.h> 
   51 #include <pcl/point_types.h> 
   92 void dump2csv(
const sensor_msgs::PointCloud2ConstPtr &cloud, 
int x_offset, 
int y_offset, 
int z_offset)
 
   95   char szFileName[255] = {0};
 
   96   sprintf(szFileName,
"/tmp/cloud_dump_%04d.csv", cnt);
 
   98   fout = fopen(szFileName,
"w");
 
  102     fprintf(fout,
"%-8s;%-8s;%-8s;%-8s;%-8s;%-8s\n",
"X(col)",
"Y(Col)",
"X",
"Y",
"Z",
"Range");
 
  103     for (i = 0; i < cloud->height; i++)
 
  105       for (j = 0; j < cloud->width; j++)
 
  107         float xRange,yRange,zRange;
 
  109         memcpy(&xRange, &(cloud->data[x_offset]), 
sizeof(
float));
 
  110         memcpy(&yRange, &(cloud->data[y_offset]), 
sizeof(
float));
 
  111         memcpy(&zRange, &(cloud->data[z_offset]), 
sizeof(
float));
 
  112         range = sqrt(xRange*xRange + yRange*yRange + zRange*zRange);
 
  113         fprintf(fout,
"%5d;%5d;", i, j);
 
  114         fprintf(fout,
"%8.3f;%8.3f;%8.3f;%8.3f", xRange, yRange, zRange, range);
 
  117         x_offset += cloud->point_step;
 
  118         y_offset += cloud->point_step;
 
  119         z_offset += cloud->point_step;
 
  141   sensor_msgs::Image 
msg;
 
  142   sensor_msgs::Image msgVGA;
 
  148   int conversionTask = 3;
 
  149   float range_eps = 0.1;
 
  152   int heightUsed = cloud->height;
 
  161   for (
size_t d = 0; 
d < cloud->fields.size(); ++
d)
 
  163     if (cloud->fields[
d].name == 
"intensity")
 
  165       rgb_index = 
static_cast<int>(
d); 
 
  168     if (cloud->fields[
d].name == 
"x")
 
  170       x_index = 
static_cast<int>(
d);
 
  173     if (cloud->fields[
d].name == 
"y")
 
  175       y_index = 
static_cast<int>(
d);
 
  178     if (cloud->fields[
d].name == 
"z")
 
  180       z_index = 
static_cast<int>(
d);
 
  193       throw std::runtime_error(
"No intensity entry!!");
 
  199   int heightStretch = 5;
 
  201   int imgChannelCnt = 0;
 
  203   const int maxAllowedEncodings = 2;
 
  204   bool encodeFlagArray[maxAllowedEncodings] = {0};
 
  205   bool useHDFormat = 
false;
 
  206   if (conversionTask & 1)
 
  208     encodeFlagArray[0] = 
true;
 
  211   if (conversionTask & 2)
 
  213     encodeFlagArray[1] = 
true;
 
  217   if (cloud->width == 0 && heightUsed == 0)
 
  219     throw std::runtime_error(
"Needs to be a dense like cloud!!");
 
  223     msg.height = heightStretch * heightUsed * imgChannelCnt;
 
  224     msg.width = cloud->width;
 
  227       if (1080 > 
msg.height)
 
  231       if (1920 > 
msg.width)
 
  237   int rgb_offset = cloud->fields[rgb_index].offset;
 
  238   int x_offset = cloud->fields[x_index].offset;
 
  239   int y_offset = cloud->fields[y_index].offset;
 
  240   int z_offset = cloud->fields[z_index].offset;
 
  244   int point_step = cloud->point_step;
 
  253     dump2csv(cloud, x_offset, y_offset, z_offset);
 
  256   msg.encoding = 
"bgr8";
 
  257   msg.step = 
static_cast<uint32_t
>(
msg.width * 
sizeof(uint8_t) * 3);
 
  261   int maxY = imgChannelCnt * heightStretch * heightUsed;
 
  263   for (
size_t y = 0; y < heightUsed; y++)
 
  265     for (
size_t x = 0; x < cloud->width; x++)
 
  267       for (
int chIdx = 0; chIdx < imgChannelCnt; chIdx++)
 
  271         for (
int j = 0; j < maxAllowedEncodings; j++)
 
  273           if (encodeFlagArray[j])
 
  275             if (chIdx == encodingCnt)
 
  284         for (
int rowInner = 0; rowInner < heightStretch; rowInner++)
 
  286           int rowTmp = (y * heightStretch + rowInner);
 
  287           rowTmp += encodingCnt * heightStretch * heightUsed;
 
  289           int rowInnerIdx = maxY - (rowTmp) - 1;
 
  291           xTmp = cloud->width - 1 - x;
 
  292           uint8_t *pixel = &(
msg.data[rowInnerIdx * 
msg.step + xTmp * 3]);
 
  293           uint8_t *pixelVGA = NULL;
 
  300           memcpy(&xRange, &(cloud->data[x_offset]), 
sizeof(
float));
 
  301           memcpy(&yRange, &(cloud->data[y_offset]), 
sizeof(
float));
 
  302           memcpy(&zRange, &(cloud->data[z_offset]), 
sizeof(
float));
 
  303           range = sqrt(xRange * xRange + yRange * yRange + zRange * zRange);
 
  304           memcpy(&intensity, &(cloud->data[rgb_offset]), 
sizeof(
float));
 
  305           if (intensity > 255.0)
 
  313           unsigned char r, g, b;
 
  314           unsigned char grey = 0;
 
  317             grey = (
unsigned char) intensity;
 
  325             bool setBlack = 
false;
 
  326             if (range < range_eps)
 
  330             if (range < minRealRange)
 
  332               range = minRealRange;
 
  335             if (range > maxRealRange)
 
  337               range = maxRealRange;
 
  343             grey = (
unsigned char) range;
 
  369       rgb_offset += point_step;
 
  370       x_offset += point_step;
 
  371       y_offset += point_step;
 
  372       z_offset += point_step;
 
  384   printf(
"sick_pcl_converter <input_pointcloud2-topic> <output_image-topic>");
 
  390   bool dumpCsvFlag = 
false;
 
  400   std::string inputTopic = argv[1];
 
  401   std::string outputTopic = argv[2];
 
  402   ros::init(argc, argv, 
"sick_pcl_converter");
 
  409   nh.
getParam(
"dump_csv", dumpCsvFlag);
 
  415     ROS_INFO(
"Dump to csv file for debugging enabled.\n Files will be dumped at /tmp ");
 
  420   if (heatMap.length() > 0)
 
  422     std::string heatMapFileName = path + 
"/config/" + heatMap;
 
  426   ROS_INFO(
"Subscribing to %s and publishing images to %s\n", inputTopic.c_str(), outputTopic.c_str());