viewer.cpp
Go to the documentation of this file.
1 
18 #include <stdlib.h>
19 #include <stdio.h>
20 #include <iostream>
21 #include <sstream>
22 #include <string>
23 #include <vector>
24 #include <cmath>
25 #include <mutex>
26 #include <thread>
27 #include <chrono>
28 
29 #include <pcl/point_cloud.h>
30 #include <pcl/point_types.h>
31 #include <pcl/io/pcd_io.h>
32 #include <pcl/visualization/cloud_viewer.h>
33 
34 #include <opencv2/opencv.hpp>
35 
36 #include <ros/ros.h>
37 #include <ros/spinner.h>
38 #include <sensor_msgs/CameraInfo.h>
39 #include <sensor_msgs/Image.h>
40 
41 #include <cv_bridge/cv_bridge.h>
42 
45 
50 
52 
53 class Receiver
54 {
55 public:
56  enum Mode
57  {
58  IMAGE = 0,
61  };
62 
63 private:
64  std::mutex lock;
65 
66  const std::string topicColor, topicDepth;
67  const bool useExact, useCompressed;
68 
70  bool save;
71  bool running;
72  size_t frame;
73  const size_t queueSize;
74 
75  cv::Mat color, depth;
77  cv::Mat lookupX, lookupY;
78 
81 
87 
90 
91  std::thread imageViewerThread;
93 
94  pcl::PointCloud<pcl::PointXYZRGBA>::Ptr cloud;
95  pcl::PCDWriter writer;
96  std::ostringstream oss;
97  std::vector<int> params;
98 
99 public:
100  Receiver(const std::string &topicColor, const std::string &topicDepth, const bool useExact, const bool useCompressed)
101  : topicColor(topicColor), topicDepth(topicDepth), useExact(useExact), useCompressed(useCompressed),
102  updateImage(false), updateCloud(false), save(false), running(false), frame(0), queueSize(5),
103  nh("~"), spinner(0), it(nh), mode(CLOUD)
104  {
105  cameraMatrixColor = cv::Mat::zeros(3, 3, CV_64F);
106  cameraMatrixDepth = cv::Mat::zeros(3, 3, CV_64F);
107  params.push_back(cv::IMWRITE_JPEG_QUALITY);
108  params.push_back(100);
109  params.push_back(cv::IMWRITE_PNG_COMPRESSION);
110  params.push_back(1);
111  params.push_back(cv::IMWRITE_PNG_STRATEGY);
112  params.push_back(cv::IMWRITE_PNG_STRATEGY_RLE);
113  params.push_back(0);
114  }
115 
117  {
118  }
119 
120  void run(const Mode mode)
121  {
122  start(mode);
123  stop();
124  }
125 
126 private:
127  void start(const Mode mode)
128  {
129  this->mode = mode;
130  running = true;
131 
132  std::string topicCameraInfoColor = topicColor.substr(0, topicColor.rfind('/')) + "/camera_info";
133  std::string topicCameraInfoDepth = topicDepth.substr(0, topicDepth.rfind('/')) + "/camera_info";
134 
135  image_transport::TransportHints hints(useCompressed ? "compressed" : "raw");
136  subImageColor = new image_transport::SubscriberFilter(it, topicColor, queueSize, hints);
137  subImageDepth = new image_transport::SubscriberFilter(it, topicDepth, queueSize, hints);
138  subCameraInfoColor = new message_filters::Subscriber<sensor_msgs::CameraInfo>(nh, topicCameraInfoColor, queueSize);
139  subCameraInfoDepth = new message_filters::Subscriber<sensor_msgs::CameraInfo>(nh, topicCameraInfoDepth, queueSize);
140 
141  if(useExact)
142  {
144  syncExact->registerCallback(boost::bind(&Receiver::callback, this, _1, _2, _3, _4));
145  }
146  else
147  {
149  syncApproximate->registerCallback(boost::bind(&Receiver::callback, this, _1, _2, _3, _4));
150  }
151 
152  spinner.start();
153 
154  std::chrono::milliseconds duration(1);
155  while(!updateImage || !updateCloud)
156  {
157  if(!ros::ok())
158  {
159  return;
160  }
161  std::this_thread::sleep_for(duration);
162  }
163  cloud = pcl::PointCloud<pcl::PointXYZRGBA>::Ptr(new pcl::PointCloud<pcl::PointXYZRGBA>());
164  cloud->height = color.rows;
165  cloud->width = color.cols;
166  cloud->is_dense = false;
167  cloud->points.resize(cloud->height * cloud->width);
168  createLookup(this->color.cols, this->color.rows);
169 
170  switch(mode)
171  {
172  case CLOUD:
173  cloudViewer();
174  break;
175  case IMAGE:
176  imageViewer();
177  break;
178  case BOTH:
179  imageViewerThread = std::thread(&Receiver::imageViewer, this);
180  cloudViewer();
181  break;
182  }
183  }
184 
185  void stop()
186  {
187  spinner.stop();
188 
189  if(useExact)
190  {
191  delete syncExact;
192  }
193  else
194  {
195  delete syncApproximate;
196  }
197 
198  delete subImageColor;
199  delete subImageDepth;
200  delete subCameraInfoColor;
201  delete subCameraInfoDepth;
202 
203  running = false;
204  if(mode == BOTH)
205  {
206  imageViewerThread.join();
207  }
208  }
209 
210  void callback(const sensor_msgs::Image::ConstPtr imageColor, const sensor_msgs::Image::ConstPtr imageDepth,
211  const sensor_msgs::CameraInfo::ConstPtr cameraInfoColor, const sensor_msgs::CameraInfo::ConstPtr cameraInfoDepth)
212  {
213  cv::Mat color, depth;
214 
215  readCameraInfo(cameraInfoColor, cameraMatrixColor);
216  readCameraInfo(cameraInfoDepth, cameraMatrixDepth);
217  readImage(imageColor, color);
218  readImage(imageDepth, depth);
219 
220  // IR image input
221  if(color.type() == CV_16U)
222  {
223  cv::Mat tmp;
224  color.convertTo(tmp, CV_8U, 0.02);
225  cv::cvtColor(tmp, color, CV_GRAY2BGR);
226  }
227 
228  lock.lock();
229  this->color = color;
230  this->depth = depth;
231  updateImage = true;
232  updateCloud = true;
233  lock.unlock();
234  }
235 
236  void imageViewer()
237  {
238  cv::Mat color, depth, depthDisp, combined;
239  std::chrono::time_point<std::chrono::high_resolution_clock> start, now;
240  double fps = 0;
241  size_t frameCount = 0;
242  std::ostringstream oss;
243  const cv::Point pos(5, 15);
244  const cv::Scalar colorText = CV_RGB(255, 255, 255);
245  const double sizeText = 0.5;
246  const int lineText = 1;
247  const int font = cv::FONT_HERSHEY_SIMPLEX;
248 
249  cv::namedWindow("Image Viewer");
250  oss << "starting...";
251 
252  start = std::chrono::high_resolution_clock::now();
253  for(; running && ros::ok();)
254  {
255  if(updateImage)
256  {
257  lock.lock();
258  color = this->color;
259  depth = this->depth;
260  updateImage = false;
261  lock.unlock();
262 
263  ++frameCount;
264  now = std::chrono::high_resolution_clock::now();
265  double elapsed = std::chrono::duration_cast<std::chrono::milliseconds>(now - start).count() / 1000.0;
266  if(elapsed >= 1.0)
267  {
268  fps = frameCount / elapsed;
269  oss.str("");
270  oss << "fps: " << fps << " ( " << elapsed / frameCount * 1000.0 << " ms)";
271  start = now;
272  frameCount = 0;
273  }
274 
275  dispDepth(depth, depthDisp, 12000.0f);
276  combine(color, depthDisp, combined);
277  //combined = color;
278 
279  cv::putText(combined, oss.str(), pos, font, sizeText, colorText, lineText, CV_AA);
280  cv::imshow("Image Viewer", combined);
281  }
282 
283  int key = cv::waitKey(1);
284  switch(key & 0xFF)
285  {
286  case 27:
287  case 'q':
288  running = false;
289  break;
290  case ' ':
291  case 's':
292  if(mode == IMAGE)
293  {
294  createCloud(depth, color, cloud);
295  saveCloudAndImages(cloud, color, depth, depthDisp);
296  }
297  else
298  {
299  save = true;
300  }
301  break;
302  }
303  }
304  cv::destroyAllWindows();
305  cv::waitKey(100);
306  }
307 
308  void cloudViewer()
309  {
310  cv::Mat color, depth;
311  pcl::visualization::PCLVisualizer::Ptr visualizer(new pcl::visualization::PCLVisualizer("Cloud Viewer"));
312  const std::string cloudName = "rendered";
313 
314  lock.lock();
315  color = this->color;
316  depth = this->depth;
317  updateCloud = false;
318  lock.unlock();
319 
320  createCloud(depth, color, cloud);
321 
322  visualizer->addPointCloud(cloud, cloudName);
323  visualizer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, cloudName);
324  visualizer->initCameraParameters();
325  visualizer->setBackgroundColor(0, 0, 0);
326  visualizer->setPosition(mode == BOTH ? color.cols : 0, 0);
327  visualizer->setSize(color.cols, color.rows);
328  visualizer->setShowFPS(true);
329  visualizer->setCameraPosition(0, 0, 0, 0, -1, 0);
330  visualizer->registerKeyboardCallback(&Receiver::keyboardEvent, *this);
331 
332  for(; running && ros::ok();)
333  {
334  if(updateCloud)
335  {
336  lock.lock();
337  color = this->color;
338  depth = this->depth;
339  updateCloud = false;
340  lock.unlock();
341 
342  createCloud(depth, color, cloud);
343 
344  visualizer->updatePointCloud(cloud, cloudName);
345  }
346  if(save)
347  {
348  save = false;
349  cv::Mat depthDisp;
350  dispDepth(depth, depthDisp, 12000.0f);
351  saveCloudAndImages(cloud, color, depth, depthDisp);
352  }
353  visualizer->spinOnce(10);
354  }
355  visualizer->close();
356  }
357 
358  void keyboardEvent(const pcl::visualization::KeyboardEvent &event, void *)
359  {
360  if(event.keyUp())
361  {
362  switch(event.getKeyCode())
363  {
364  case 27:
365  case 'q':
366  running = false;
367  break;
368  case ' ':
369  case 's':
370  save = true;
371  break;
372  }
373  }
374  }
375 
376  void readImage(const sensor_msgs::Image::ConstPtr msgImage, cv::Mat &image) const
377  {
379  pCvImage = cv_bridge::toCvShare(msgImage, msgImage->encoding);
380  pCvImage->image.copyTo(image);
381  }
382 
383  void readCameraInfo(const sensor_msgs::CameraInfo::ConstPtr cameraInfo, cv::Mat &cameraMatrix) const
384  {
385  double *itC = cameraMatrix.ptr<double>(0, 0);
386  for(size_t i = 0; i < 9; ++i, ++itC)
387  {
388  *itC = cameraInfo->K[i];
389  }
390  }
391 
392  void dispDepth(const cv::Mat &in, cv::Mat &out, const float maxValue)
393  {
394  cv::Mat tmp = cv::Mat(in.rows, in.cols, CV_8U);
395  const uint32_t maxInt = 255;
396 
397  #pragma omp parallel for
398  for(int r = 0; r < in.rows; ++r)
399  {
400  const uint16_t *itI = in.ptr<uint16_t>(r);
401  uint8_t *itO = tmp.ptr<uint8_t>(r);
402 
403  for(int c = 0; c < in.cols; ++c, ++itI, ++itO)
404  {
405  *itO = (uint8_t)std::min((*itI * maxInt / maxValue), 255.0f);
406  }
407  }
408 
409  cv::applyColorMap(tmp, out, cv::COLORMAP_JET);
410  }
411 
412  void combine(const cv::Mat &inC, const cv::Mat &inD, cv::Mat &out)
413  {
414  out = cv::Mat(inC.rows, inC.cols, CV_8UC3);
415 
416  #pragma omp parallel for
417  for(int r = 0; r < inC.rows; ++r)
418  {
419  const cv::Vec3b
420  *itC = inC.ptr<cv::Vec3b>(r),
421  *itD = inD.ptr<cv::Vec3b>(r);
422  cv::Vec3b *itO = out.ptr<cv::Vec3b>(r);
423 
424  for(int c = 0; c < inC.cols; ++c, ++itC, ++itD, ++itO)
425  {
426  itO->val[0] = (itC->val[0] + itD->val[0]) >> 1;
427  itO->val[1] = (itC->val[1] + itD->val[1]) >> 1;
428  itO->val[2] = (itC->val[2] + itD->val[2]) >> 1;
429  }
430  }
431  }
432 
433  void createCloud(const cv::Mat &depth, const cv::Mat &color, pcl::PointCloud<pcl::PointXYZRGBA>::Ptr &cloud) const
434  {
435  const float badPoint = std::numeric_limits<float>::quiet_NaN();
436 
437  #pragma omp parallel for
438  for(int r = 0; r < depth.rows; ++r)
439  {
440  pcl::PointXYZRGBA *itP = &cloud->points[r * depth.cols];
441  const uint16_t *itD = depth.ptr<uint16_t>(r);
442  const cv::Vec3b *itC = color.ptr<cv::Vec3b>(r);
443  const float y = lookupY.at<float>(0, r);
444  const float *itX = lookupX.ptr<float>();
445 
446  for(size_t c = 0; c < (size_t)depth.cols; ++c, ++itP, ++itD, ++itC, ++itX)
447  {
448  register const float depthValue = *itD / 1000.0f;
449  // Check for invalid measurements
450  if(*itD == 0)
451  {
452  // not valid
453  itP->x = itP->y = itP->z = badPoint;
454  itP->rgba = 0;
455  continue;
456  }
457  itP->z = depthValue;
458  itP->x = *itX * depthValue;
459  itP->y = y * depthValue;
460  itP->b = itC->val[0];
461  itP->g = itC->val[1];
462  itP->r = itC->val[2];
463  itP->a = 255;
464  }
465  }
466  }
467 
468  void saveCloudAndImages(const pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr cloud, const cv::Mat &color, const cv::Mat &depth, const cv::Mat &depthColored)
469  {
470  oss.str("");
471  oss << "./" << std::setfill('0') << std::setw(4) << frame;
472  const std::string baseName = oss.str();
473  const std::string cloudName = baseName + "_cloud.pcd";
474  const std::string colorName = baseName + "_color.jpg";
475  const std::string depthName = baseName + "_depth.png";
476  const std::string depthColoredName = baseName + "_depth_colored.png";
477 
478  OUT_INFO("saving cloud: " << cloudName);
479  writer.writeBinary(cloudName, *cloud);
480  OUT_INFO("saving color: " << colorName);
481  cv::imwrite(colorName, color, params);
482  OUT_INFO("saving depth: " << depthName);
483  cv::imwrite(depthName, depth, params);
484  OUT_INFO("saving depth: " << depthColoredName);
485  cv::imwrite(depthColoredName, depthColored, params);
486  OUT_INFO("saving complete!");
487  ++frame;
488  }
489 
490  void createLookup(size_t width, size_t height)
491  {
492  const float fx = 1.0f / cameraMatrixColor.at<double>(0, 0);
493  const float fy = 1.0f / cameraMatrixColor.at<double>(1, 1);
494  const float cx = cameraMatrixColor.at<double>(0, 2);
495  const float cy = cameraMatrixColor.at<double>(1, 2);
496  float *it;
497 
498  lookupY = cv::Mat(1, height, CV_32F);
499  it = lookupY.ptr<float>();
500  for(size_t r = 0; r < height; ++r, ++it)
501  {
502  *it = (r - cy) * fy;
503  }
504 
505  lookupX = cv::Mat(1, width, CV_32F);
506  it = lookupX.ptr<float>();
507  for(size_t c = 0; c < width; ++c, ++it)
508  {
509  *it = (c - cx) * fx;
510  }
511  }
512 };
513 
514 void help(const std::string &path)
515 {
516  std::cout << path << FG_BLUE " [options]" << std::endl
517  << FG_GREEN " name" NO_COLOR ": " FG_YELLOW "'any string'" NO_COLOR " equals to the kinect2_bridge topic base name" << std::endl
518  << FG_GREEN " mode" NO_COLOR ": " FG_YELLOW "'qhd'" NO_COLOR ", " FG_YELLOW "'hd'" NO_COLOR ", " FG_YELLOW "'sd'" NO_COLOR " or " FG_YELLOW "'ir'" << std::endl
519  << FG_GREEN " visualization" NO_COLOR ": " FG_YELLOW "'image'" NO_COLOR ", " FG_YELLOW "'cloud'" NO_COLOR " or " FG_YELLOW "'both'" << std::endl
520  << FG_GREEN " options" NO_COLOR ":" << std::endl
521  << FG_YELLOW " 'compressed'" NO_COLOR " use compressed instead of raw topics" << std::endl
522  << FG_YELLOW " 'approx'" NO_COLOR " use approximate time synchronization" << std::endl;
523 }
524 
525 int main(int argc, char **argv)
526 {
527 #if EXTENDED_OUTPUT
529  if(!getenv("ROSCONSOLE_FORMAT"))
530  {
532  ros::console::g_formatter.init("[${severity}] ${message}");
533  }
534 #endif
535 
536  ros::init(argc, argv, "kinect2_viewer", ros::init_options::AnonymousName);
537 
538  if(!ros::ok())
539  {
540  return 0;
541  }
542 
543  std::string ns = K2_DEFAULT_NS;
545  std::string topicDepth = K2_TOPIC_QHD K2_TOPIC_IMAGE_DEPTH K2_TOPIC_IMAGE_RECT;
546  bool useExact = true;
547  bool useCompressed = false;
549 
550  for(size_t i = 1; i < (size_t)argc; ++i)
551  {
552  std::string param(argv[i]);
553 
554  if(param == "-h" || param == "--help" || param == "-?" || param == "--?")
555  {
556  help(argv[0]);
557  ros::shutdown();
558  return 0;
559  }
560  else if(param == "qhd")
561  {
562  topicColor = K2_TOPIC_QHD K2_TOPIC_IMAGE_COLOR K2_TOPIC_IMAGE_RECT;
563  topicDepth = K2_TOPIC_QHD K2_TOPIC_IMAGE_DEPTH K2_TOPIC_IMAGE_RECT;
564  }
565  else if(param == "hd")
566  {
567  topicColor = K2_TOPIC_HD K2_TOPIC_IMAGE_COLOR K2_TOPIC_IMAGE_RECT;
568  topicDepth = K2_TOPIC_HD K2_TOPIC_IMAGE_DEPTH K2_TOPIC_IMAGE_RECT;
569  }
570  else if(param == "ir")
571  {
572  topicColor = K2_TOPIC_SD K2_TOPIC_IMAGE_IR K2_TOPIC_IMAGE_RECT;
573  topicDepth = K2_TOPIC_SD K2_TOPIC_IMAGE_DEPTH K2_TOPIC_IMAGE_RECT;
574  }
575  else if(param == "sd")
576  {
577  topicColor = K2_TOPIC_SD K2_TOPIC_IMAGE_COLOR K2_TOPIC_IMAGE_RECT;
578  topicDepth = K2_TOPIC_SD K2_TOPIC_IMAGE_DEPTH K2_TOPIC_IMAGE_RECT;
579  }
580  else if(param == "approx")
581  {
582  useExact = false;
583  }
584 
585  else if(param == "compressed")
586  {
587  useCompressed = true;
588  }
589  else if(param == "image")
590  {
591  mode = Receiver::IMAGE;
592  }
593  else if(param == "cloud")
594  {
595  mode = Receiver::CLOUD;
596  }
597  else if(param == "both")
598  {
599  mode = Receiver::BOTH;
600  }
601  else
602  {
603  ns = param;
604  }
605  }
606 
607  topicColor = "/" + ns + topicColor;
608  topicDepth = "/" + ns + topicDepth;
609  OUT_INFO("topic color: " FG_CYAN << topicColor << NO_COLOR);
610  OUT_INFO("topic depth: " FG_CYAN << topicDepth << NO_COLOR);
611 
612  Receiver receiver(topicColor, topicDepth, useExact, useCompressed);
613 
614  OUT_INFO("starting receiver...");
615  receiver.run(mode);
616 
617  ros::shutdown();
618  return 0;
619 }
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
image_transport::ImageTransport it
Definition: viewer.cpp:84
bool param(const std::string &param_name, T &param_val, const T &default_val)
Mode mode
Definition: viewer.cpp:92
message_filters::Synchronizer< ApproximateSyncPolicy > * syncApproximate
Definition: viewer.cpp:89
#define K2_TOPIC_SD
#define K2_TOPIC_IMAGE_COLOR
Receiver(const std::string &topicColor, const std::string &topicDepth, const bool useExact, const bool useCompressed)
Definition: viewer.cpp:100
void readCameraInfo(const sensor_msgs::CameraInfo::ConstPtr cameraInfo, cv::Mat &cameraMatrix) const
Definition: viewer.cpp:383
~Receiver()
Definition: viewer.cpp:116
#define K2_TOPIC_IMAGE_IR
pcl::PCDWriter writer
Definition: viewer.cpp:95
#define FG_GREEN
#define K2_DEFAULT_NS
f
#define FG_YELLOW
const size_t queueSize
Definition: viewer.cpp:73
void run(const Mode mode)
Definition: viewer.cpp:120
cv::Mat lookupY
Definition: viewer.cpp:77
cv::Mat lookupX
Definition: viewer.cpp:77
message_filters::Subscriber< sensor_msgs::CameraInfo > * subCameraInfoColor
Definition: viewer.cpp:86
void createCloud(const cv::Mat &depth, const cv::Mat &color, pcl::PointCloud< pcl::PointXYZRGBA >::Ptr &cloud) const
Definition: viewer.cpp:433
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void dispDepth(const cv::Mat &in, cv::Mat &out, const float maxValue)
Definition: viewer.cpp:392
bool save
Definition: viewer.cpp:70
message_filters::Subscriber< sensor_msgs::CameraInfo > * subCameraInfoDepth
Definition: viewer.cpp:86
#define OUT_INFO(msg)
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo > ApproximateSyncPolicy
Definition: viewer.cpp:80
const std::string topicColor
Definition: viewer.cpp:66
#define ROSCONSOLE_AUTOINIT
ros::NodeHandle nh
Definition: viewer.cpp:82
TFSIMD_FORCE_INLINE const tfScalar & y() const
void start(const Mode mode)
Definition: viewer.cpp:127
image_transport::SubscriberFilter * subImageDepth
Definition: viewer.cpp:85
void readImage(const sensor_msgs::Image::ConstPtr msgImage, cv::Mat &image) const
Definition: viewer.cpp:376
void imageViewer()
Definition: viewer.cpp:236
message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo > ExactSyncPolicy
Definition: viewer.cpp:79
#define K2_TOPIC_QHD
void init(const char *fmt)
bool updateCloud
Definition: viewer.cpp:69
Connection registerCallback(C &callback)
void combine(const cv::Mat &inC, const cv::Mat &inD, cv::Mat &out)
Definition: viewer.cpp:412
message_filters::Synchronizer< ExactSyncPolicy > * syncExact
Definition: viewer.cpp:88
cv::Mat color
Definition: viewer.cpp:75
ROSCPP_DECL bool ok()
std::mutex lock
Definition: viewer.cpp:64
void createLookup(size_t width, size_t height)
Definition: viewer.cpp:490
bool updateImage
Definition: viewer.cpp:69
#define K2_TOPIC_IMAGE_DEPTH
void stop()
Definition: viewer.cpp:185
#define FG_BLUE
ros::AsyncSpinner spinner
Definition: viewer.cpp:83
#define FG_CYAN
size_t frame
Definition: viewer.cpp:72
void callback(const sensor_msgs::Image::ConstPtr imageColor, const sensor_msgs::Image::ConstPtr imageDepth, const sensor_msgs::CameraInfo::ConstPtr cameraInfoColor, const sensor_msgs::CameraInfo::ConstPtr cameraInfoDepth)
Definition: viewer.cpp:210
void cloudViewer()
Definition: viewer.cpp:308
#define NO_COLOR
const std::string topicDepth
Definition: viewer.cpp:66
bool running
Definition: viewer.cpp:71
ROSCPP_DECL void shutdown()
void keyboardEvent(const pcl::visualization::KeyboardEvent &event, void *)
Definition: viewer.cpp:358
cv::Mat depth
Definition: viewer.cpp:75
void help(const std::string &path)
Definition: viewer.cpp:514
pcl::PointCloud< pcl::PointXYZRGBA >::Ptr cloud
Definition: viewer.cpp:94
ROSCONSOLE_DECL Formatter g_formatter
cv::Mat cameraMatrixColor
Definition: viewer.cpp:76
std::vector< int > params
Definition: viewer.cpp:97
cv::Mat cameraMatrixDepth
Definition: viewer.cpp:76
int main(int argc, char **argv)
Definition: viewer.cpp:525
const bool useCompressed
Definition: viewer.cpp:67
#define K2_TOPIC_HD
image_transport::SubscriberFilter * subImageColor
Definition: viewer.cpp:85
#define K2_TOPIC_IMAGE_RECT
void saveCloudAndImages(const pcl::PointCloud< pcl::PointXYZRGBA >::ConstPtr cloud, const cv::Mat &color, const cv::Mat &depth, const cv::Mat &depthColored)
Definition: viewer.cpp:468
std::thread imageViewerThread
Definition: viewer.cpp:91
const bool useExact
Definition: viewer.cpp:67
std::ostringstream oss
Definition: viewer.cpp:96


kinect2_viewer
Author(s):
autogenerated on Wed Jan 3 2018 03:48:12