Test Intel RealSense SR300 acquisition.
#include <iostream>
#include <visp3/core/vpImageConvert.h>
#include <visp3/gui/vpDisplayGDI.h>
#include <visp3/gui/vpDisplayX.h>
#include <visp3/io/vpImageIo.h>
#include <visp3/sensor/vpRealSense.h>
#if defined(VISP_HAVE_REALSENSE) && defined(VISP_HAVE_CPP11_COMPATIBILITY) && \
(defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI))
#include <mutex>
#include <thread>
#ifdef VISP_HAVE_PCL
#include <pcl/visualization/cloud_viewer.h>
#include <pcl/visualization/pcl_visualizer.h>
#endif
namespace
{
#ifdef VISP_HAVE_PCL
pcl::PointCloud<pcl::PointXYZ>::Ptr pointcloud(new pcl::PointCloud<pcl::PointXYZ>());
pcl::PointCloud<pcl::PointXYZRGB>::Ptr pointcloud_color(new pcl::PointCloud<pcl::PointXYZRGB>());
bool cancelled = false, update_pointcloud = false;
class ViewerWorker
{
public:
explicit ViewerWorker(const bool color_mode, std::mutex &mutex) : m_colorMode(color_mode), m_mutex(mutex) {}
void run()
{
pcl::visualization::PCLVisualizer::Ptr viewer(new pcl::visualization::PCLVisualizer("3D Viewer " + date));
pcl::visualization::PointCloudColorHandlerRGBField<pcl::PointXYZRGB> rgb(pointcloud_color);
pcl::PointCloud<pcl::PointXYZ>::Ptr local_pointcloud(new pcl::PointCloud<pcl::PointXYZ>());
pcl::PointCloud<pcl::PointXYZRGB>::Ptr local_pointcloud_color(new pcl::PointCloud<pcl::PointXYZRGB>());
viewer->setBackgroundColor(0, 0, 0);
viewer->initCameraParameters();
viewer->setPosition(640 + 80, 480 + 80);
viewer->setCameraPosition(0, 0, -0.25, 0, -1, 0);
viewer->setSize(640, 480);
bool init = true;
bool local_update = false, local_cancelled = false;
while (!local_cancelled) {
{
std::unique_lock<std::mutex> lock(m_mutex, std::try_to_lock);
if (lock.owns_lock()) {
local_update = update_pointcloud;
update_pointcloud = false;
local_cancelled = cancelled;
if (local_update) {
if (m_colorMode) {
local_pointcloud_color = pointcloud_color->makeShared();
} else {
local_pointcloud = pointcloud->makeShared();
}
}
}
}
if (local_update && !local_cancelled) {
local_update = false;
if (init) {
if (m_colorMode) {
viewer->addPointCloud<pcl::PointXYZRGB>(local_pointcloud_color, rgb, "RGB sample cloud");
viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1,
"RGB sample cloud");
} else {
viewer->addPointCloud<pcl::PointXYZ>(local_pointcloud, "sample cloud");
viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "sample cloud");
}
init = false;
} else {
if (m_colorMode) {
viewer->updatePointCloud<pcl::PointXYZRGB>(local_pointcloud_color, rgb, "RGB sample cloud");
} else {
viewer->updatePointCloud<pcl::PointXYZ>(local_pointcloud, "sample cloud");
}
}
}
viewer->spinOnce(5);
}
std::cout << "End of point cloud display thread" << std::endl;
}
private:
bool m_colorMode;
std::mutex &m_mutex;
};
#endif //#ifdef VISP_HAVE_PCL
void test_SR300(
vpRealSense &rs,
const std::map<rs::stream, bool> &enables,
const std::map<rs::stream, vpRealSense::vpRsStreamParams> ¶ms, const std::string &title,
const bool depth_color_visualization = false, const rs::stream &color_stream = rs::stream::color,
const rs::stream &depth_stream = rs::stream::depth, bool display_pcl = false, bool pcl_color = false)
{
std::cout << std::endl;
std::map<rs::stream, bool>::const_iterator it_enable;
std::map<rs::stream, vpRealSense::vpRsStreamParams>::const_iterator it_param;
for (it_enable = enables.begin(), it_param = params.begin(); it_enable != enables.end(); ++it_enable) {
if (it_enable->second) {
it_param = params.find(it_enable->first);
if (it_param != params.end()) {
}
}
}
bool direct_infrared_conversion = false;
for (it_enable = enables.begin(); it_enable != enables.end(); ++it_enable) {
if (it_enable->second) {
switch (it_enable->first) {
case rs::stream::color:
break;
case rs::stream::depth:
break;
case rs::stream::infrared:
it_param = params.find(it_enable->first);
if (it_param != params.end()) {
direct_infrared_conversion = it_param->second.m_streamFormat == rs::format::y8;
}
break;
default:
break;
}
}
}
#if defined(VISP_HAVE_X11)
#elif defined(VISP_HAVE_GDI)
#endif
for (it_enable = enables.begin(); it_enable != enables.end(); ++it_enable) {
if (it_enable->second) {
switch (it_enable->first) {
case rs::stream::color:
dc.
init(I_color, 0, 0,
"Color frame");
break;
case rs::stream::depth:
if (depth_color_visualization) {
dd.
init(I_depth_color, (
int)I_color.
getWidth() + 80, 0,
"Depth frame");
} else {
dd.
init(I_depth, (
int)I_color.
getWidth() + 80, 0,
"Depth frame");
}
break;
case rs::stream::infrared:
break;
default:
break;
}
}
}
if (rs.
getHandler()->is_stream_enabled(rs::stream::infrared)) {
std::cout << "direct_infrared_conversion=" << direct_infrared_conversion << std::endl;
}
#ifdef VISP_HAVE_PCL
std::mutex mutex;
ViewerWorker viewer(pcl_color, mutex);
std::thread viewer_thread;
if (display_pcl) {
viewer_thread = std::thread(&ViewerWorker::run, &viewer);
}
#else
display_pcl = false;
#endif
std::vector<double> time_vector;
while (true) {
if (display_pcl) {
#ifdef VISP_HAVE_PCL
std::lock_guard<std::mutex> lock(mutex);
if (direct_infrared_conversion) {
if (pcl_color) {
rs.
acquire((
unsigned char *)I_color.
bitmap, (
unsigned char *)depth.
bitmap, NULL, pointcloud_color,
(
unsigned char *)I_infrared.
bitmap, NULL, color_stream, depth_stream);
} else {
(
unsigned char *)I_infrared.
bitmap, NULL, color_stream, depth_stream);
}
} else {
if (pcl_color) {
rs.
acquire((
unsigned char *)I_color.
bitmap, (
unsigned char *)depth.
bitmap, NULL, pointcloud_color,
(
unsigned char *)infrared.
bitmap, NULL, color_stream, depth_stream);
} else {
(
unsigned char *)infrared.
bitmap, NULL, color_stream, depth_stream);
}
}
update_pointcloud = true;
#endif
} else {
if (direct_infrared_conversion) {
(
unsigned char *)I_infrared.
bitmap, NULL, color_stream, depth_stream);
} else {
(
unsigned char *)infrared.
bitmap, NULL, color_stream, depth_stream);
}
}
if (depth_color_visualization) {
} else {
}
if (depth_color_visualization) {
} else {
}
if (depth_color_visualization) {
} else {
}
break;
}
break;
}
}
if (display_pcl) {
#ifdef VISP_HAVE_PCL
{
std::lock_guard<std::mutex> lock(mutex);
cancelled = true;
}
viewer_thread.join();
#endif
}
}
}
int main(int argc, char *argv[])
{
try {
if (rs_get_device_name((
const rs_device *)rs.
getHandler(),
nullptr) != std::string(
"Intel RealSense SR300")) {
std::cout << "This test file is used to test the Intel RealSense SR300 only." << std::endl;
return EXIT_SUCCESS;
}
std::cout << "API version: " << rs_get_api_version(nullptr) << std::endl;
std::cout <<
"Firmware: " << rs_get_device_firmware_version((
const rs_device *)rs.
getHandler(),
nullptr)
<< std::endl;
std::cout << "RealSense sensor characteristics: \n" << rs << std::endl;
std::map<rs::stream, bool> enables;
std::map<rs::stream, vpRealSense::vpRsStreamParams> params;
enables[rs::stream::color] = false;
enables[rs::stream::depth] = true;
enables[rs::stream::infrared] = false;
test_SR300(rs, enables, params, "SR300_DEPTH_Z16_640x240_110FPS");
enables[rs::stream::color] = true;
enables[rs::stream::depth] = false;
enables[rs::stream::infrared] = false;
test_SR300(rs, enables, params, "SR300_COLOR_RGBA8_1920x1080_30FPS");
enables[rs::stream::color] = false;
enables[rs::stream::depth] = false;
enables[rs::stream::infrared] = true;
test_SR300(rs, enables, params, "SR300_INFRARED_Y16_640x480_200FPS");
enables[rs::stream::color] = false;
enables[rs::stream::depth] = true;
enables[rs::stream::infrared] = false;
test_SR300(rs, enables, params, "SR300_DEPTH_Z16_640x480_60FPS", true);
enables[rs::stream::color] = false;
enables[rs::stream::depth] = true;
enables[rs::stream::infrared] = true;
test_SR300(rs, enables, params, "SR300_DEPTH_Z16_640x480_60FPS + SR300_INFRARED_Y8_640x480_60FPS", true);
#if (!defined(__APPLE__) && !defined(__MACH__)) // Not OSX, since viewer->spinOnce (10); produces a
enables[rs::stream::color] = true;
enables[rs::stream::depth] = true;
enables[rs::stream::infrared] = true;
rs::stream color_stream = argc > 1 ? (rs::stream)atoi(argv[1]) : rs::stream::color;
std::cout << "\ncolor_stream: " << color_stream << std::endl;
rs::stream depth_stream = argc > 2 ? (rs::stream)atoi(argv[2]) : rs::stream::depth;
std::cout << "depth_stream: " << depth_stream << std::endl;
test_SR300(rs, enables, params,
"SR300_COLOR_RGBA8_640x480_60FPS + "
"SR300_DEPTH_Z16_640x480_60FPS + "
"SR300_INFRARED_Y8_640x480_60FPS",
true, color_stream, depth_stream, true, true);
#endif
enables[rs::stream::color] = true;
enables[rs::stream::depth] = true;
enables[rs::stream::infrared] = false;
test_SR300(rs, enables, params,
"SR300_COLOR_ALIGNED_TO_DEPTH_RGBA8_640x480_30FPS + "
"SR300_DEPTH_Z16_640x480_30FPS",
true, rs::stream::color_aligned_to_depth);
test_SR300(rs, enables, params,
"SR300_COLOR_RGBA8_640x480_30FPS + "
"SR300_DEPTH_ALIGNED_TO_COLOR_Z16_640x480_30FPS",
true, rs::stream::color, rs::stream::depth_aligned_to_color);
#if VISP_HAVE_OPENCV_VERSION >= 0x020409
cv::Mat color_mat(480, 640, CV_8UC3);
cv::Mat infrared_mat(480, 640, CV_8U);
while (true) {
rs.
acquire(color_mat.data, NULL, NULL, infrared_mat.data);
cv::imshow("Color mat", color_mat);
cv::imshow("Infrared mat", infrared_mat);
char c = cv::waitKey(1);
if (c == 27) {
break;
}
break;
}
}
#endif
std::cerr <<
"RealSense error " << e.
what() << std::endl;
} catch (const rs::error &e) {
std::cerr << "RealSense error calling " << e.get_failed_function() << "(" << e.get_failed_args()
<< "): " << e.what() << std::endl;
} catch (const std::exception &e) {
std::cerr << e.what() << std::endl;
}
return EXIT_SUCCESS;
}
#else
int main()
{
#if !defined(VISP_HAVE_REALSENSE)
std::cout << "Install librealsense to make this test work." << std::endl;
#endif
#if !defined(VISP_HAVE_CPP11_COMPATIBILITY)
std::cout << "Build ViSP with C++11 compiler flag (cmake -DUSE_CPP11=ON) "
"to make this test work."
<< std::endl;
#endif
#if !defined(VISP_HAVE_X11) && !defined(VISP_HAVE_GDI)
std::cout << "X11 or GDI are needed." << std::endl;
#endif
return EXIT_SUCCESS;
}
#endif