47 #include <visp3/core/vpImageConvert.h> 48 #include <visp3/core/vpMutex.h> 49 #include <visp3/core/vpThread.h> 50 #include <visp3/gui/vpDisplayGDI.h> 51 #include <visp3/gui/vpDisplayX.h> 52 #include <visp3/sensor/vpRealSense.h> 54 #if defined(VISP_HAVE_REALSENSE) && defined(VISP_HAVE_CPP11_COMPATIBILITY) 58 #if (!defined(__APPLE__) && !defined(__MACH__)) // Not OSX 59 #if (defined(VISP_HAVE_PTHREAD) || defined(_WIN32)) // Threading available 65 #include <pcl/visualization/cloud_viewer.h> 66 #include <pcl/visualization/pcl_visualizer.h> 72 typedef enum { capture_waiting, capture_started, capture_stopped } t_CaptureState;
73 t_CaptureState s_capture_state = capture_waiting;
78 pcl::PointCloud<pcl::PointXYZRGB>::Ptr pointcloud_ = *((pcl::PointCloud<pcl::PointXYZRGB>::Ptr *)args);
80 pcl::visualization::PCLVisualizer::Ptr viewer(
new pcl::visualization::PCLVisualizer(
"3D Viewer"));
81 pcl::visualization::PointCloudColorHandlerRGBField<pcl::PointXYZRGB> rgb(pointcloud_);
82 viewer->setBackgroundColor(0, 0, 0);
83 viewer->initCameraParameters();
84 viewer->setPosition(640 + 80, 480 + 80);
85 viewer->setCameraPosition(0, 0, -0.5, 0, -1, 0);
86 viewer->setSize(640, 480);
88 t_CaptureState capture_state_;
91 s_mutex_capture.
lock();
92 capture_state_ = s_capture_state;
95 if (capture_state_ == capture_started) {
96 static bool update =
false;
98 viewer->addPointCloud<pcl::PointXYZRGB>(pointcloud_, rgb,
"sample cloud");
99 viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1,
"sample cloud");
102 viewer->updatePointCloud<pcl::PointXYZRGB>(pointcloud_, rgb,
"sample cloud");
105 viewer->spinOnce(10);
107 }
while (capture_state_ != capture_stopped);
109 std::cout <<
"End of point cloud display thread" << std::endl;
118 #if defined(VISP_HAVE_REALSENSE) && defined(VISP_HAVE_CPP11_COMPATIBILITY) 128 std::cout <<
"Extrinsics cMd: \n" << rs.
getTransformation(rs::stream::color, rs::stream::depth) << std::endl;
129 std::cout <<
"Extrinsics dMc: \n" << rs.
getTransformation(rs::stream::depth, rs::stream::color) << std::endl;
130 std::cout <<
"Extrinsics cMi: \n" << rs.
getTransformation(rs::stream::color, rs::stream::infrared) << std::endl;
131 std::cout <<
"Extrinsics dMi: \n" << rs.
getTransformation(rs::stream::depth, rs::stream::infrared) << std::endl;
140 bool use_infrared_y16 = dev->get_stream_format(rs::stream::infrared) == rs::format::y16;
147 pcl::PointCloud<pcl::PointXYZRGB>::Ptr pointcloud(
new pcl::PointCloud<pcl::PointXYZRGB>);
152 pcl::visualization::PCLVisualizer::Ptr viewer(
new pcl::visualization::PCLVisualizer(
"3D Viewer"));
153 pcl::visualization::PointCloudColorHandlerRGBField<pcl::PointXYZRGB> rgb(pointcloud);
154 viewer->setBackgroundColor(0, 0, 0);
155 viewer->addCoordinateSystem(1.0);
156 viewer->initCameraParameters();
157 viewer->setCameraPosition(0, 0, -0.5, 0, -1, 0);
161 std::vector<vpColVector> pointcloud;
164 #if defined(VISP_HAVE_X11) 166 vpDisplayX di(infrared_display, (
int)color.getWidth() + 80, 10,
"Infrared image");
167 vpDisplayX dd(depth_display, 10, (
int)color.getHeight() + 80,
"Depth image");
168 #elif defined(VISP_HAVE_GDI) 170 vpDisplayGDI di(infrared_display, color.getWidth() + 80, 10,
"Infrared image");
171 vpDisplayGDI dd(depth_display, 10, color.getHeight() + 80,
"Depth image");
173 std::cout <<
"No image viewer is available..." << std::endl;
179 if (use_infrared_y16) {
180 rs.
acquire(color, infrared_y16, depth, pointcloud);
184 rs.
acquire((
unsigned char *)color.bitmap, (
unsigned char *)depth.bitmap, NULL, pointcloud,
185 (
unsigned char *)infrared_display.bitmap);
187 rs.
acquire((
unsigned char *)color.bitmap, (
unsigned char *)depth.bitmap, NULL,
188 (
unsigned char *)infrared_display.bitmap);
196 s_capture_state = capture_started;
199 static bool update =
false;
201 viewer->addPointCloud<pcl::PointXYZRGB>(pointcloud, rgb,
"sample cloud");
202 viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1,
"sample cloud");
203 viewer->setPosition(color.getWidth() + 80, color.getHeight() + 80);
206 viewer->updatePointCloud<pcl::PointXYZRGB>(pointcloud, rgb,
"sample cloud");
209 viewer->spinOnce(10);
231 std::cout <<
"RealSense sensor characteristics: \n" << rs << std::endl;
237 s_capture_state = capture_stopped;
244 std::cerr <<
"RealSense error " << e.
what() << std::endl;
245 }
catch (
const rs::error &e) {
246 std::cerr <<
"RealSense error calling " << e.get_failed_function() <<
"(" << e.get_failed_args()
247 <<
"): " << e.what() << std::endl;
248 }
catch (
const std::exception &e) {
249 std::cerr << e.what() << std::endl;
252 #elif !defined(VISP_HAVE_REALSENSE) 253 std::cout <<
"Install RealSense SDK to make this test working" << std::endl;
254 std::cout <<
"Tip:" << std::endl;
255 std::cout <<
"- After installation, configure again ViSP using cmake and build again this example" << std::endl;
256 #elif !defined(VISP_HAVE_CPP11_COMPATIBILITY) 257 std::cout <<
"You do not build ViSP with C++11 compiler flag" << std::endl;
258 std::cout <<
"Tip:" << std::endl;
259 std::cout <<
"- Configure ViSP again using cmake -DUSE_CPP11=ON, and build again this example" << std::endl;
Class that allows protection by mutex.
vpHomogeneousMatrix getTransformation(const rs::stream &from, const rs::stream &to) const
static bool getClick(const vpImage< unsigned char > &I, bool blocking=true)
static void convert(const vpImage< unsigned char > &src, vpImage< vpRGBa > &dest)
rs::device * getHandler() const
Get access to device handler.
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...
error that can be emited by ViSP classes.
void acquire(std::vector< vpColVector > &pointcloud)
static void flush(const vpImage< unsigned char > &I)
VISP_EXPORT double measureTimeMs()
const char * what() const
static void display(const vpImage< unsigned char > &I)
rs::intrinsics getIntrinsics(const rs::stream &stream) const
void setStreamSettings(const rs::stream &stream, const rs::preset &preset)
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)