3 #include <visp3/core/vpConfig.h> 4 #if (defined (VISP_HAVE_REALSENSE) || defined (VISP_HAVE_REALSENSE2)) && defined (VISP_HAVE_CPP11_COMPATIBILITY) && (defined (VISP_HAVE_X11) || defined (VISP_HAVE_GDI)) 10 #include <condition_variable> 12 #if defined (VISP_HAVE_PCL) 13 #include <pcl/common/common.h> 14 #include <pcl/io/pcd_io.h> 17 #include <visp3/core/vpImageConvert.h> 18 #include <visp3/core/vpIoTools.h> 19 #include <visp3/core/vpXmlParserCamera.h> 20 #include <visp3/gui/vpDisplayX.h> 21 #include <visp3/gui/vpDisplayGDI.h> 22 #include <visp3/io/vpParseArgv.h> 23 #include <visp3/io/vpImageIo.h> 24 #include <visp3/sensor/vpRealSense.h> 25 #include <visp3/sensor/vpRealSense2.h> 28 #if defined (VISP_HAVE_REALSENSE2) 29 #define USE_REALSENSE2 32 #define GETOPTARGS "so:acdpiCf:bh" 35 void usage(
const char *name,
const char *badparam) {
37 Save RealSense data.\n\ 48 Use aligned streams.\n\ 60 Save infrared stream.\n\ 69 Save point cloud in binary format.\n\ 76 fprintf(stdout,
"\nERROR: Bad parameter [%s]\n", badparam);
79 bool getOptions(
int argc,
char **argv,
81 std::string &output_directory,
82 bool &use_aligned_stream,
85 bool &save_pointcloud,
89 bool &save_pointcloud_binary_format
92 const char **argv1=(
const char**)argv;
97 case 's': save =
true;
break;
98 case 'o': output_directory = optarg;
break;
99 case 'a': use_aligned_stream =
true;
break;
100 case 'c': save_color =
true;
break;
101 case 'd': save_depth =
true;
break;
102 case 'p': save_pointcloud =
true;
break;
103 case 'i': save_infrared =
true;
break;
104 case 'C': click_to_save =
true;
break;
105 case 'f': stream_fps = atoi(optarg);
break;
106 case 'b': save_pointcloud_binary_format =
true;
break;
108 case 'h': usage(argv[0], NULL);
return false;
break;
111 usage(argv[0], optarg);
116 if ((c == 1) || (c == -1)) {
118 usage(argv[0], NULL);
119 std::cerr <<
"ERROR: " << std::endl;
120 std::cerr <<
" Bad argument " << optarg << std::endl << std::endl;
132 FrameQueue() : m_cancelled(false), m_cond(),
133 m_queueColor(), m_queueDepth(), m_queuePointCloud(),
135 m_maxQueueSize(1024*8), m_mutex() {
139 std::lock_guard<std::mutex> lock(m_mutex);
147 const pcl::PointCloud<pcl::PointXYZ>::Ptr &pointCloud,
149 const std::vector<vpColVector> &pointCloud,
152 std::lock_guard<std::mutex> lock(m_mutex);
154 m_queueColor.push(colorImg);
155 m_queueDepth.push(depthImg);
156 m_queuePointCloud.push(pointCloud);
157 m_queueInfrared.push(infraredImg);
160 while(m_queueColor.size() > m_maxQueueSize) {
165 while(m_queueDepth.size() > m_maxQueueSize) {
170 while(m_queuePointCloud.size() > m_maxQueueSize) {
171 m_queuePointCloud.pop();
175 while(m_queueInfrared.size() > m_maxQueueSize) {
176 m_queueInfrared.pop();
185 pcl::PointCloud<pcl::PointXYZ>::Ptr &pointCloud,
187 std::vector<vpColVector> &pointCloud,
190 std::unique_lock<std::mutex> lock(m_mutex);
192 while (m_queueColor.empty() || m_queueDepth.empty() || m_queuePointCloud.empty() || m_queueInfrared.empty()) {
204 colorImg = m_queueColor.front();
205 depthImg = m_queueDepth.front();
206 pointCloud = m_queuePointCloud.front();
207 infraredImg = m_queueInfrared.front();
211 m_queuePointCloud.pop();
212 m_queueInfrared.pop();
215 void setMaxQueueSize(
const size_t max_queue_size) {
216 m_maxQueueSize = max_queue_size;
221 std::condition_variable m_cond;
222 std::queue<vpImage<vpRGBa> > m_queueColor;
223 std::queue<vpImage<uint16_t> > m_queueDepth;
225 std::queue<pcl::PointCloud<pcl::PointXYZ>::Ptr> m_queuePointCloud;
227 std::queue<std::vector<vpColVector> > m_queuePointCloud;
229 std::queue<vpImage<unsigned char> > m_queueInfrared;
230 size_t m_maxQueueSize;
234 class StorageWorker {
236 StorageWorker(FrameQueue &queue,
const std::string &directory,
const bool save_color,
237 const bool save_depth,
const bool save_pointcloud,
const bool save_infrared,
238 const bool save_pointcloud_binary_format,
int 239 #ifndef VISP_HAVE_PCL
243 #ifndef VISP_HAVE_PCL
247 m_queue(queue), m_directory(directory), m_cpt(0), m_save_color(save_color), m_save_depth(save_depth),
248 m_save_pointcloud(save_pointcloud), m_save_infrared(save_infrared),
249 m_save_pointcloud_binary_format(save_pointcloud_binary_format)
250 #ifndef VISP_HAVE_PCL
251 , m_size_height(height), m_size_width(width)
262 pcl::PointCloud<pcl::PointXYZ>::Ptr pointCloud;
264 std::vector<vpColVector> pointCloud;
270 m_queue.pop(colorImg, depthImg, pointCloud, infraredImg);
272 if (!m_directory.empty()) {
273 std::stringstream ss;
276 ss << m_directory <<
"/color_image_%04d.jpg";
277 sprintf(buffer, ss.str().c_str(), m_cpt);
279 std::string filename_color = buffer;
285 ss << m_directory <<
"/depth_image_%04d.bin";
286 sprintf(buffer, ss.str().c_str(), m_cpt);
287 std::string filename_depth = buffer;
289 std::ofstream file_depth(filename_depth.c_str(), std::ios::out | std::ios::binary);
290 if (file_depth.is_open()) {
296 for (
unsigned int i = 0; i < height; i++) {
297 for (
unsigned int j = 0; j < width; j++) {
298 value = depthImg[i][j];
305 if (m_save_pointcloud) {
307 ss << m_directory <<
"/point_cloud_%04d" << (m_save_pointcloud_binary_format ?
".bin" :
".pcd");
308 sprintf(buffer, ss.str().c_str(), m_cpt);
309 std::string filename_point_cloud = buffer;
311 if (m_save_pointcloud_binary_format) {
312 std::ofstream file_pointcloud(filename_point_cloud.c_str(), std::ios::out | std::ios::binary);
314 if (file_pointcloud.is_open()) {
316 uint32_t width = pointCloud->width;
317 uint32_t height = pointCloud->height;
319 char is_dense = pointCloud->is_dense;
323 file_pointcloud.write( (
char *)(&is_dense),
sizeof(is_dense) );
325 for (uint32_t i = 0; i < height; i++) {
326 for (uint32_t j = 0; j < width; j++) {
327 pcl::PointXYZ pt = (*pointCloud)(j,i);
335 uint32_t width = m_size_width;
336 uint32_t height = m_size_height;
342 file_pointcloud.write( (
char *)(&is_dense),
sizeof(is_dense) );
344 for (uint32_t i = 0; i < height; i++) {
345 for (uint32_t j = 0; j < width; j++) {
346 float x = (float) pointCloud[i*width + j][0];
347 float y = (float) pointCloud[i*width + j][1];
348 float z = (float) pointCloud[i*width + j][2];
359 pcl::io::savePCDFileBinary(filename_point_cloud, *pointCloud);
364 if (m_save_infrared) {
366 ss << m_directory <<
"/infrared_image_%04d.jpg";
367 sprintf(buffer, ss.str().c_str(), m_cpt);
369 std::string filename_infrared = buffer;
376 }
catch (
const FrameQueue::cancelled &) {
377 std::cout <<
"Receive cancel FrameQueue." << std::endl;
383 std::string m_directory;
387 bool m_save_pointcloud;
388 bool m_save_infrared;
389 bool m_save_pointcloud_binary_format;
390 #ifndef VISP_HAVE_PCL 397 int main(
int argc,
char *argv[]) {
400 std::string output_directory_custom =
"";
401 bool use_aligned_stream =
false;
402 bool save_color =
false;
403 bool save_depth =
false;
404 bool save_pointcloud =
false;
405 bool save_infrared =
false;
406 bool click_to_save =
false;
408 bool save_pointcloud_binary_format =
false;
411 if (!getOptions(argc, argv, save, output_directory_custom, use_aligned_stream, save_color, save_depth,
412 save_pointcloud, save_infrared, click_to_save, stream_fps, save_pointcloud_binary_format)) {
416 if (!output_directory_custom.empty())
417 output_directory = output_directory_custom +
"/" + output_directory;
419 #ifndef VISP_HAVE_PCL 420 save_pointcloud_binary_format =
true;
423 std::cout <<
"save: " << save << std::endl;
424 std::cout <<
"output_directory: " << output_directory << std::endl;
425 std::cout <<
"use_aligned_stream: " << use_aligned_stream << std::endl;
426 std::cout <<
"save_color: " << save_color << std::endl;
427 std::cout <<
"save_depth: " << save_depth << std::endl;
428 std::cout <<
"save_pointcloud: " << save_pointcloud << std::endl;
429 std::cout <<
"save_infrared: " << save_infrared << std::endl;
430 std::cout <<
"stream_fps: " << stream_fps << std::endl;
431 std::cout <<
"save_pointcloud_binary_format: " << save_pointcloud_binary_format << std::endl;
432 std::cout <<
"click_to_save: " << click_to_save << std::endl;
434 int width = 640, height = 480;
435 #ifdef USE_REALSENSE2 439 config.enable_stream(RS2_STREAM_COLOR, width, height, RS2_FORMAT_RGBA8, stream_fps);
440 config.enable_stream(RS2_STREAM_DEPTH, width, height, RS2_FORMAT_Z16, stream_fps);
441 config.enable_stream(RS2_STREAM_INFRARED, width, height, RS2_FORMAT_Y8, stream_fps);
442 realsense.
open(config);
464 d1.
init(I_gray, 0, 0,
"RealSense color stream");
465 d2.
init(I_depth, I_gray.getWidth()+80, 0,
"RealSense depth stream");
466 d3.
init(I_infrared, I_gray.getWidth()+80, I_gray.getHeight()+10,
"RealSense infrared stream");
469 realsense.
acquire((
unsigned char *) I_color.bitmap, (
unsigned char *) I_depth_raw.bitmap, NULL, NULL);
489 #ifdef USE_REALSENSE2 492 xml_camera.
save(cam_color, output_directory+
"/camera.xml",
"color_camera", width, height);
495 xml_camera.
save(cam_depth, output_directory+
"/camera.xml",
"depth_camera", width, height);
498 xml_camera.
save(cam_infrared, output_directory+
"/camera.xml",
"infrared_camera", width, height);
504 xml_camera.
save(cam_color, output_directory+
"/camera.xml",
"color_camera", width, height);
507 xml_camera.
save(cam_color_rectified, output_directory+
"/camera.xml",
"color_camera_rectified", width, height);
510 xml_camera.
save(cam_depth, output_directory+
"/camera.xml",
"depth_camera", width, height);
513 xml_camera.
save(cam_depth_aligned_to_rectified_color, output_directory+
"/camera.xml",
"depth_camera_aligned_to_rectified_color", width, height);
516 xml_camera.
save(cam_infrared, output_directory+
"/camera.xml",
"infrared_camera", width, height);
520 std::ofstream file( std::string(output_directory+
"/depth_M_color.txt") );
521 depth_M_color.
save(file);
525 FrameQueue save_queue;
526 StorageWorker storage(std::ref(save_queue), std::cref(output_directory), save_color, save_depth, save_pointcloud, save_infrared,
527 save_pointcloud_binary_format, width, height);
528 std::thread storage_thread(&StorageWorker::run, &storage);
530 #ifdef USE_REALSENSE2 531 rs2::align align_to(RS2_STREAM_COLOR);
532 if (use_aligned_stream && save_infrared) {
533 std::cerr <<
"Cannot use aligned streams with infrared acquisition currently." 534 "\nInfrared stream acquisition is disabled!" << std::endl;
541 pcl::PointCloud<pcl::PointXYZ>::Ptr pointCloud(
new pcl::PointCloud<pcl::PointXYZ>);
543 std::vector<vpColVector> pointCloud;
546 if (use_aligned_stream) {
547 #ifdef USE_REALSENSE2 549 realsense.
acquire((
unsigned char *) I_color.bitmap, (
unsigned char *) I_depth_raw.bitmap, NULL, pointCloud, NULL,
552 realsense.
acquire((
unsigned char *) I_color.bitmap, (
unsigned char *) I_depth_raw.bitmap, &pointCloud, NULL,
557 realsense.
acquire((
unsigned char *) I_color.bitmap, (
unsigned char *) I_depth_raw.bitmap, NULL, pointCloud, (
unsigned char *) I_infrared.bitmap,
558 NULL, rs::stream::rectified_color, rs::stream::depth_aligned_to_rectified_color);
560 realsense.
acquire((
unsigned char *) I_color.bitmap, (
unsigned char *) I_depth_raw.bitmap, &pointCloud, (
unsigned char *) I_infrared.bitmap,
561 NULL, rs::stream::rectified_color, rs::stream::depth_aligned_to_rectified_color);
566 realsense.
acquire((
unsigned char *) I_color.bitmap, (
unsigned char *) I_depth_raw.bitmap, NULL, pointCloud, (
unsigned char *) I_infrared.bitmap,
569 realsense.
acquire((
unsigned char *) I_color.bitmap, (
unsigned char *) I_depth_raw.bitmap, &pointCloud, (
unsigned char *) I_infrared.bitmap);
580 if (!click_to_save) {
583 std::stringstream ss;
584 ss <<
"Images saved:" << nb_saves;
592 if (save && !click_to_save) {
594 pcl::PointCloud<pcl::PointXYZ>::Ptr pointCloud_copy = pointCloud->makeShared();
595 save_queue.push(I_color, I_depth_raw, pointCloud_copy, I_infrared);
597 save_queue.push(I_color, I_depth_raw, pointCloud, I_infrared);
603 if (!click_to_save) {
612 pcl::PointCloud<pcl::PointXYZ>::Ptr pointCloud_copy = pointCloud->makeShared();
613 save_queue.push(I_color, I_depth_raw, pointCloud_copy, I_infrared);
615 save_queue.push(I_color, I_depth_raw, pointCloud, I_infrared);
631 storage_thread.join();
637 std::cerr <<
"Need libRealSense or libRealSense2 and C++11 and displayX or displayGDI!" << std::endl;
vpHomogeneousMatrix getTransformation(const rs::stream &from, const rs::stream &to) const
static bool getClick(const vpImage< unsigned char > &I, bool blocking=true)
unsigned int getWidth() const
static void convert(const vpImage< unsigned char > &src, vpImage< vpRGBa > &dest)
Implementation of an homogeneous matrix and operations on such kind of matrices.
Display for windows using GDI (available on any windows 32 platform).
static void displayText(const vpImage< unsigned char > &I, const vpImagePoint &ip, const std::string &s, const vpColor &color)
Use the X11 console to display images on unix-like OS. Thus to enable this class X11 should be instal...
void acquire(std::vector< vpColVector > &pointcloud)
void open(const rs2::config &cfg=rs2::config())
XML parser to load and save intrinsic camera parameters.
static void flush(const vpImage< unsigned char > &I)
VISP_EXPORT std::string getDateTime(const std::string &format="%Y/%m/%d %H:%M:%S")
static bool parse(int *argcPtr, const char **argv, vpArgvInfo *argTable, int flags)
static void write(const vpImage< unsigned char > &I, const std::string &filename)
static void display(const vpImage< unsigned char > &I)
Generic class defining intrinsic camera parameters.
void save(std::ofstream &f) const
void setStreamSettings(const rs::stream &stream, const rs::preset &preset)
unsigned int getHeight() const
void init(vpImage< unsigned char > &I, int winx=-1, int winy=-1, const std::string &title="")
int save(const vpCameraParameters &cam, const std::string &filename, const std::string &camera_name, const unsigned int image_width=0, const unsigned int image_height=0, const std::string &additionalInfo="")
vpCameraParameters getCameraParameters(const rs::stream &stream, vpCameraParameters::vpCameraParametersProjType type=vpCameraParameters::perspectiveProjWithDistortion) const
static void createDepthHistogram(const vpImage< uint16_t > &src_depth, vpImage< vpRGBa > &dest_rgba)