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> 34 #include <opencv2/opencv.hpp> 38 #include <sensor_msgs/CameraInfo.h> 39 #include <sensor_msgs/Image.h> 94 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr
cloud;
96 std::ostringstream
oss;
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)
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);
111 params.push_back(cv::IMWRITE_PNG_STRATEGY);
112 params.push_back(cv::IMWRITE_PNG_STRATEGY_RLE);
132 std::string topicCameraInfoColor = topicColor.substr(0, topicColor.rfind(
'/')) +
"/camera_info";
133 std::string topicCameraInfoDepth = topicDepth.substr(0, topicDepth.rfind(
'/')) +
"/camera_info";
154 std::chrono::milliseconds duration(1);
155 while(!updateImage || !updateCloud)
161 std::this_thread::sleep_for(duration);
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);
206 imageViewerThread.join();
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)
221 if(color.type() == CV_16U)
224 color.convertTo(tmp, CV_8U, 0.02);
225 cv::cvtColor(tmp, color, CV_GRAY2BGR);
239 std::chrono::time_point<std::chrono::high_resolution_clock>
start, now;
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;
249 cv::namedWindow(
"Image Viewer");
250 oss <<
"starting...";
252 start = std::chrono::high_resolution_clock::now();
264 now = std::chrono::high_resolution_clock::now();
265 double elapsed = std::chrono::duration_cast<std::chrono::milliseconds>(now -
start).count() / 1000.0;
268 fps = frameCount / elapsed;
270 oss <<
"fps: " << fps <<
" ( " << elapsed / frameCount * 1000.0 <<
" ms)";
276 combine(color, depthDisp, combined);
279 cv::putText(combined, oss.str(), pos, font, sizeText, colorText, lineText, CV_AA);
280 cv::imshow(
"Image Viewer", combined);
283 int key = cv::waitKey(1);
304 cv::destroyAllWindows();
311 pcl::visualization::PCLVisualizer::Ptr visualizer(
new pcl::visualization::PCLVisualizer(
"Cloud Viewer"));
312 const std::string cloudName =
"rendered";
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);
344 visualizer->updatePointCloud(cloud, cloudName);
353 visualizer->spinOnce(10);
362 switch(event.getKeyCode())
376 void readImage(
const sensor_msgs::Image::ConstPtr msgImage, cv::Mat &image)
const 380 pCvImage->image.copyTo(image);
383 void readCameraInfo(
const sensor_msgs::CameraInfo::ConstPtr cameraInfo, cv::Mat &cameraMatrix)
const 385 double *itC = cameraMatrix.ptr<
double>(0, 0);
386 for(
size_t i = 0; i < 9; ++i, ++itC)
388 *itC = cameraInfo->K[i];
392 void dispDepth(
const cv::Mat &in, cv::Mat &out,
const float maxValue)
394 cv::Mat tmp = cv::Mat(in.rows, in.cols, CV_8U);
395 const uint32_t maxInt = 255;
397 #pragma omp parallel for 398 for(
int r = 0; r < in.rows; ++r)
400 const uint16_t *itI = in.ptr<uint16_t>(r);
401 uint8_t *itO = tmp.ptr<uint8_t>(r);
403 for(
int c = 0; c < in.cols; ++c, ++itI, ++itO)
405 *itO = (uint8_t)std::min((*itI * maxInt / maxValue), 255.0f);
409 cv::applyColorMap(tmp, out, cv::COLORMAP_JET);
412 void combine(
const cv::Mat &inC,
const cv::Mat &inD, cv::Mat &out)
414 out = cv::Mat(inC.rows, inC.cols, CV_8UC3);
416 #pragma omp parallel for 417 for(
int r = 0; r < inC.rows; ++r)
420 *itC = inC.ptr<cv::Vec3b>(r),
421 *itD = inD.ptr<cv::Vec3b>(r);
422 cv::Vec3b *itO = out.ptr<cv::Vec3b>(r);
424 for(
int c = 0; c < inC.cols; ++c, ++itC, ++itD, ++itO)
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;
433 void createCloud(
const cv::Mat &depth,
const cv::Mat &color, pcl::PointCloud<pcl::PointXYZRGBA>::Ptr &cloud)
const 435 const float badPoint = std::numeric_limits<float>::quiet_NaN();
437 #pragma omp parallel for 438 for(
int r = 0; r < depth.rows; ++r)
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>();
446 for(
size_t c = 0; c < (size_t)depth.cols; ++c, ++itP, ++itD, ++itC, ++itX)
448 register const float depthValue = *itD / 1000.0f;
453 itP->x = itP->y = itP->z = badPoint;
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];
468 void saveCloudAndImages(
const pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr cloud,
const cv::Mat &color,
const cv::Mat &depth,
const cv::Mat &depthColored)
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";
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);
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);
498 lookupY = cv::Mat(1, height, CV_32F);
499 it = lookupY.ptr<
float>();
500 for(
size_t r = 0; r < height; ++r, ++
it)
505 lookupX = cv::Mat(1, width, CV_32F);
506 it = lookupX.ptr<
float>();
507 for(
size_t c = 0; c < width; ++c, ++
it)
514 void help(
const std::string &path)
516 std::cout << path <<
FG_BLUE " [options]" << 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;
525 int main(
int argc,
char **argv)
529 if(!getenv(
"ROSCONSOLE_FORMAT"))
550 for(
size_t i = 1; i < (size_t)argc; ++i)
552 std::string
param(argv[i]);
554 if(param ==
"-h" || param ==
"--help" || param ==
"-?" || param ==
"--?")
560 else if(param ==
"qhd")
565 else if(param ==
"hd")
570 else if(param ==
"ir")
575 else if(param ==
"sd")
580 else if(param ==
"approx")
585 else if(param ==
"compressed")
587 useCompressed =
true;
589 else if(param ==
"image")
593 else if(param ==
"cloud")
597 else if(param ==
"both")
612 Receiver receiver(topicColor, topicDepth, useExact, useCompressed);
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
image_transport::ImageTransport it
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val)
message_filters::Synchronizer< ApproximateSyncPolicy > * syncApproximate
#define K2_TOPIC_IMAGE_COLOR
Receiver(const std::string &topicColor, const std::string &topicDepth, const bool useExact, const bool useCompressed)
void readCameraInfo(const sensor_msgs::CameraInfo::ConstPtr cameraInfo, cv::Mat &cameraMatrix) const
#define K2_TOPIC_IMAGE_IR
void run(const Mode mode)
message_filters::Subscriber< sensor_msgs::CameraInfo > * subCameraInfoColor
void createCloud(const cv::Mat &depth, const cv::Mat &color, pcl::PointCloud< pcl::PointXYZRGBA >::Ptr &cloud) const
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)
message_filters::Subscriber< sensor_msgs::CameraInfo > * subCameraInfoDepth
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo > ApproximateSyncPolicy
const std::string topicColor
#define ROSCONSOLE_AUTOINIT
TFSIMD_FORCE_INLINE const tfScalar & y() const
void start(const Mode mode)
image_transport::SubscriberFilter * subImageDepth
void readImage(const sensor_msgs::Image::ConstPtr msgImage, cv::Mat &image) const
message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo > ExactSyncPolicy
Connection registerCallback(C &callback)
void combine(const cv::Mat &inC, const cv::Mat &inD, cv::Mat &out)
message_filters::Synchronizer< ExactSyncPolicy > * syncExact
void createLookup(size_t width, size_t height)
#define K2_TOPIC_IMAGE_DEPTH
ros::AsyncSpinner spinner
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)
const std::string topicDepth
ROSCPP_DECL void shutdown()
void keyboardEvent(const pcl::visualization::KeyboardEvent &event, void *)
void help(const std::string &path)
pcl::PointCloud< pcl::PointXYZRGBA >::Ptr cloud
ROSCONSOLE_DECL Formatter g_formatter
cv::Mat cameraMatrixColor
std::vector< int > params
cv::Mat cameraMatrixDepth
int main(int argc, char **argv)
image_transport::SubscriberFilter * subImageColor
#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)
std::thread imageViewerThread