pcl_converter.cpp
Go to the documentation of this file.
1 
60 #include <ros/ros.h>
61 // PCL specific includes
62 #include <ros/package.h>
65 #include <pcl/point_cloud.h>
66 #include <pcl/point_types.h>
67 #include <math.h>
68 
69 using namespace ros;
70 
72 
74 
76 bool usingPal = false;
77 
79 
80 double minRange = 255.99 * 0.25;
81 double maxRange = 0.00;
82 float minRangeGreyVal = 0.0;
83 float maxRangeGreyVal = 255.99;
84 
85 int numEchoOutput = 1;
86 
88 {
89 private:
90  bool dump2csv;
91 public:
92  bool isDump2csv() const
93  {
94  return dump2csv;
95  }
96 
97  void setDump2csv(bool dump2csv)
98  {
100  }
101 
102 };
103 
105 
106 
107 void dump2csv(const sensor_msgs::PointCloud2ConstPtr &cloud, int x_offset, int y_offset, int z_offset)
108 {
109  static int cnt = 0;
110  char szFileName[255] = {0};
111  sprintf(szFileName,"/tmp/cloud_dump_%04d.csv", cnt);
112  FILE *fout;
113  fout = fopen(szFileName,"w");
114  if (fout != NULL)
115  {
116  int i,j;
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++)
119  {
120  for (j = 0; j < cloud->width; j++)
121  {
122  float xRange,yRange,zRange;
123  float range;
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);
130  fprintf(fout,"\n");
131 
132  x_offset += cloud->point_step;
133  y_offset += cloud->point_step;
134  z_offset += cloud->point_step;
135  }
136  }
137  }
138  fclose(fout);
139  cnt++;
140 }
141 
142 
143 
144 
145 
153 void
155 {
157  sensor_msgs::Image msgVGA;
158  int rgb_index = -1;
159  int x_index = -1;
160  int y_index = -1;
161  int z_index = -1;
162 
163  int conversionTask = 3;
164  float range_eps = 0.1;
165 
166 
167  int heightUsed = cloud->height;
168  if (numEchoOutput == 1)
169  {
170  if (heightUsed > 24)
171  {
172  heightUsed = 24;
173  }
174  }
175  // Get the index we need
176  for (size_t d = 0; d < cloud->fields.size(); ++d)
177  {
178  if (cloud->fields[d].name == "intensity")
179  {
180  rgb_index = static_cast<int>(d); // relative index for each field entry
181 
182  }
183  if (cloud->fields[d].name == "x")
184  {
185  x_index = static_cast<int>(d);
186 
187  }
188  if (cloud->fields[d].name == "y")
189  {
190  y_index = static_cast<int>(d);
191 
192  }
193  if (cloud->fields[d].name == "z")
194  {
195  z_index = static_cast<int>(d);
196 
197  }
198  }
199  if (rgb_index == -1)
200  {
202  {
203  return;
204  // intensity flag is missing - ignore the scan
205  }
206  else
207  {
208  throw std::runtime_error("No intensity entry!!");
209  }
210  }
211 
212 
213 
214  int heightStretch = 5;
215 
216  int imgChannelCnt = 0;
217 
218  const int maxAllowedEncodings = 2;
219  bool encodeFlagArray[maxAllowedEncodings] = {0};
220  bool useHDFormat = false;
221  if (conversionTask & 1)
222  {
223  encodeFlagArray[0] = true;
224  imgChannelCnt++;
225  }
226  if (conversionTask & 2)
227  {
228  encodeFlagArray[1] = true;
229  imgChannelCnt++;
230  }
231 
232  if (cloud->width == 0 && heightUsed == 0)
233  {
234  throw std::runtime_error("Needs to be a dense like cloud!!");
235  }
236  else
237  {
238  msg.height = heightStretch * heightUsed * imgChannelCnt;
239  msg.width = cloud->width;
240  if (useHDFormat)
241  {
242  if (1080 > msg.height)
243  {
244  msg.height = 1080;
245  }
246  if (1920 > msg.width)
247  {
248  msg.width = 1920;
249  }
250  }
251  }
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;
256 
257 
258 
259  int point_step = cloud->point_step;
260 
261  /*
262  * point_step: size of each element
263  * x_offset etc: relative index
264  *
265  */
267  {
268  dump2csv(cloud, x_offset, y_offset, z_offset);
269  }
270  // pcl::image_encodings::BGR8;
271  msg.encoding = "bgr8";
272  msg.step = static_cast<uint32_t>(msg.width * sizeof(uint8_t) * 3);
273  msg.data.resize(msg.step * msg.height);
274 
275 
276  int maxY = imgChannelCnt * heightStretch * heightUsed;
277 
278  for (size_t y = 0; y < heightUsed; y++)
279  {
280  for (size_t x = 0; x < cloud->width; x++)
281  {
282  for (int chIdx = 0; chIdx < imgChannelCnt; chIdx++)
283  {
284  int encodingCnt = 0;
285  int encodeIdx = -1; // Kanal, fuer den encodiert werden soll....
286  for (int j = 0; j < maxAllowedEncodings; j++)
287  {
288  if (encodeFlagArray[j])
289  {
290  if (chIdx == encodingCnt)
291  {
292  encodeIdx = j;
293  break;
294  }
295  encodingCnt++;
296  }
297  }
298 
299  for (int rowInner = 0; rowInner < heightStretch; rowInner++)
300  {
301  int rowTmp = (y * heightStretch + rowInner);
302  rowTmp += encodingCnt * heightStretch * heightUsed;
303 
304  int rowInnerIdx = maxY - (rowTmp) - 1;
305  int xTmp = x;
306  xTmp = cloud->width - 1 - x;
307  uint8_t *pixel = &(msg.data[rowInnerIdx * msg.step + xTmp * 3]);
308  uint8_t *pixelVGA = NULL;
309 
310  float intensity;
311  float xRange;
312  float yRange;
313  float zRange;
314  float range = 0.0;
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)
321  {
322  intensity = 255.0;
323  }
324  if (intensity < 0.0)
325  {
326  intensity = 0.0;
327  }
328  unsigned char r, g, b;
329  unsigned char grey = 0;
330  if (encodeIdx == 0)
331  {
332  grey = (unsigned char) intensity;
333  }
334 
335  float minRealRange = (minRange < maxRange) ? minRange : maxRange;
336  float maxRealRange = (minRange < maxRange) ? maxRange : minRange;
337 
338  if (encodeIdx == 1)
339  {
340  bool setBlack = false;
341  if (range < range_eps)
342  {
343  setBlack = true;
344  }
345  if (range < minRealRange)
346  {
347  range = minRealRange;
348 
349  }
350  if (range > maxRealRange)
351  {
352  range = maxRealRange;
353  }
354  // calculate from range to grey value
355  range = (range - minRange) / (maxRange - minRange) * (maxRangeGreyVal - minRangeGreyVal);
356  range += minRangeGreyVal;
357 
358  grey = (unsigned char) range;
359  if (setBlack)
360  {
361  grey = 0;
362  }
363  }
364 
365  // grey = 0xFF;
366  r = grey;
367  g = grey;
368  b = grey;
369 
370 
371  if (usingPal)
372  {
373  r = pal.getRbgValue(grey, 0);
374  g = pal.getRbgValue(grey, 1);
375  b = pal.getRbgValue(grey, 2);
376  }
377  pixel[2] = r;
378  pixel[1] = g;
379  pixel[0] = b;
380 
381  //memcpy(pixel, &(cloud->data[rgb_offset]), 3 * sizeof (uint8_t));
382  }
383  }
384  rgb_offset += point_step;
385  x_offset += point_step;
386  y_offset += point_step;
387  z_offset += point_step;
388 
389  }
390 
391  }
392 
393 // Publish the data.
394  pub.publish(msg);
395 }
396 
397 void argUsage()
398 {
399  printf("sick_pcl_converter <input_pointcloud2-topic> <output_image-topic>");
400 }
401 
402 int
403 main(int argc, char **argv)
404 {
405  bool dumpCsvFlag = false;
406  // Initialize ROS
407  if (argc < 3)
408  {
409  argUsage();
410  exit(-1);
411  }
412 
413  // sensor_msgs::PointCloud2 pclTmp;
414 
415  std::string inputTopic = argv[1];
416  std::string outputTopic = argv[2];
417  ros::init(argc, argv, "sick_pcl_converter");
418 
419 
420  ros::NodeHandle nh("sick_pcl_converter");
421  std::string heatMap;
422  nh.getParam("heat_map", heatMap);
423 
424  nh.getParam("dump_csv", dumpCsvFlag);
425 
426  paramSettings.setDump2csv(dumpCsvFlag);
427 
429  {
430  ROS_INFO("Dump to csv file for debugging enabled.\n Files will be dumped at /tmp ");
431  }
432 
433  std::string path = ros::package::getPath("sick_scan");
434 
435  if (heatMap.length() > 0)
436  {
437  std::string heatMapFileName = path + "/config/" + heatMap;
438  pal.load(heatMapFileName);
439  usingPal = true;
440  }
441  ROS_INFO("Subscribing to %s and publishing images to %s\n", inputTopic.c_str(), outputTopic.c_str());
442  // Create a ROS subscriber for the input point cloud
443 // ros::Subscriber sub = nh.subscribe (inputTopic, 1, cloud_cb);
444  ros::Subscriber sub = nh.subscribe(inputTopic, 1, cloud2image_cb);
445 
446 
447  // Create a ROS publisher for the output point cloud
448 // pub = nh.advertise<sensor_msgs::PointCloud2> (outputTopic, 1);
449  pub = nh.advertise<sensor_msgs::Image>(outputTopic, 1);
450 
451  // Spin
452  ros::spin();
453 }
ParamSettings::dump2csv
bool dump2csv
Definition: pcl_converter.cpp:90
msg
msg
ros::Publisher
argUsage
void argUsage()
Definition: pcl_converter.cpp:397
ros::package::getPath
ROSLIB_DECL std::string getPath(const std::string &package_name)
Returns the fully-qualified path to a package, or an empty string if the package is not found.
NULL
#define NULL
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
alternate ROS initialization function.
ros
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
GnuPlotPalette
Definition: gnuplotPaletteReader.h:5
maxRange
double maxRange
Definition: pcl_converter.cpp:81
pub
ros::Publisher pub
Definition: pcl_converter.cpp:73
ParamSettings::setDump2csv
void setDump2csv(bool dump2csv)
Definition: pcl_converter.cpp:97
paramSettings
ParamSettings paramSettings
Definition: pcl_converter.cpp:104
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
Definition: rossimu.cpp:350
GnuPlotPalette::load
int load(std::string palettName)
Definition: gnuplotPaletteReader.cpp:69
maxRangeGreyVal
float maxRangeGreyVal
Definition: pcl_converter.cpp:83
PointCloud2.h
d
d
minRange
double minRange
Definition: pcl_converter.cpp:80
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
usingPal
bool usingPal
Definition: pcl_converter.cpp:76
pal
GnuPlotPalette pal
Definition: pcl_converter.cpp:75
ROS_INFO
#define ROS_INFO(...)
Definition: sick_scan_logging.h:117
main
int main(int argc, char **argv)
Definition: pcl_converter.cpp:403
ParamSettings::isDump2csv
bool isDump2csv() const
Definition: pcl_converter.cpp:92
ignoreIntensityMissing
bool ignoreIntensityMissing
Definition: pcl_converter.cpp:78
sensor_msgs::Image_::height
_height_type height
Definition: Image.h:54
gnuplotPaletteReader.h
dump2csv
void dump2csv(const sensor_msgs::PointCloud2ConstPtr &cloud, int x_offset, int y_offset, int z_offset)
Definition: pcl_converter.cpp:107
minRangeGreyVal
float minRangeGreyVal
Definition: pcl_converter.cpp:82
ros::spin
ROSCPP_DECL void spin()
Enter simple event loop.
Definition: rossimu.cpp:260
ParamSettings
Definition: pcl_converter.cpp:87
pcl_conversions.h
numEchoOutput
int numEchoOutput
Definition: pcl_converter.cpp:85
GnuPlotPalette::getRbgValue
unsigned char getRbgValue(unsigned char greyIdx, unsigned int channelIdx)
Definition: gnuplotPaletteReader.cpp:184
cloud2image_cb
void cloud2image_cb(const sensor_msgs::PointCloud2ConstPtr &cloud)
Copy the RGB fields of a PCLPointCloud2 msg into pcl::PCLImage format.
Definition: pcl_converter.cpp:154
sensor_msgs::Image_< std::allocator< void > >
sensor_msgs::PointCloud2ConstPtr
std::shared_ptr< ::sensor_msgs::PointCloud2 const > PointCloud2ConstPtr
Definition: PointCloud2.h:93
ros::NodeHandle
ros::Subscriber


sick_scan_xd
Author(s): Michael Lehning , Jochen Sprickerhof , Martin Günther
autogenerated on Fri Oct 25 2024 02:47:09