rs-pcl-color.cpp
Go to the documentation of this file.
1 /***********************************************************
2  * Author: Daniel Tran
3  * Liam Gogley
4  *
5  * Purpose: The following .cpp file will utilize the Intel
6  * realsense camera to stream and capture frame
7  * data of the environment. Color is then applied
8  * and a point cloud is generated and saved to
9  * a point cloud data format (.pcd).
10  *
11  * Version 0.09 - Last Editted 11/07/18
12  *
13  * Rev: Implementation of RGB Texture function to map
14  * color to point cloud data.
15  *
16  ***********************************************************/
17 
18 #include <iostream>
19 #include <algorithm>
20 #include <boost/date_time/posix_time/posix_time.hpp>
21 #include <boost/thread/thread.hpp>
22 #include <string>
23 
24 // Intel Realsense Headers
25 #include <librealsense2/rs.hpp> // Include RealSense Cross Platform API
26 
27 // PCL Headers
28 #include <pcl/io/pcd_io.h>
29 #include <pcl/point_types.h>
30 #include <pcl/filters/passthrough.h>
31 #include <pcl/common/common_headers.h>
32 #include <pcl/features/normal_3d.h>
33 #include <pcl/visualization/pcl_visualizer.h>
34 #include <pcl/console/parse.h>
35 #include <boost/thread/thread.hpp>
36 #include <pcl/io/io.h>
37 #include <pcl/visualization/cloud_viewer.h>
38 
39 using namespace std;
40 
41 typedef pcl::PointXYZRGB RGB_Cloud;
42 typedef pcl::PointCloud<RGB_Cloud> point_cloud;
43 typedef point_cloud::Ptr cloud_pointer;
44 typedef point_cloud::Ptr prevCloud;
45 
46 // Prototypes
47 void Load_PCDFile(void);
48 bool userInput(void);
49 void cloudViewer(void);
50 
51 // Global Variables
52 string cloudFile; // .pcd file name
53 string prevCloudFile; // .pcd file name (Old cloud)
54 int i = 1; // Index for incremental file name
55 
56 //======================================================
57 // RGB Texture
58 // - Function is utilized to extract the RGB data from
59 // a single point return R, G, and B values.
60 // Normals are stored as RGB components and
61 // correspond to the specific depth (XYZ) coordinate.
62 // By taking these normals and converting them to
63 // texture coordinates, the RGB components can be
64 // "mapped" to each individual point (XYZ).
65 //======================================================
66 std::tuple<int, int, int> RGB_Texture(rs2::video_frame texture, rs2::texture_coordinate Texture_XY)
67 {
68  // Get Width and Height coordinates of texture
69  int width = texture.get_width(); // Frame width in pixels
70  int height = texture.get_height(); // Frame height in pixels
71 
72  // Normals to Texture Coordinates conversion
73  int x_value = min(max(int(Texture_XY.u * width + .5f), 0), width - 1);
74  int y_value = min(max(int(Texture_XY.v * height + .5f), 0), height - 1);
75 
76  int bytes = x_value * texture.get_bytes_per_pixel(); // Get # of bytes per pixel
77  int strides = y_value * texture.get_stride_in_bytes(); // Get line width in bytes
78  int Text_Index = (bytes + strides);
79 
80  const auto New_Texture = reinterpret_cast<const uint8_t*>(texture.get_data());
81 
82  // RGB components to save in tuple
83  int NT1 = New_Texture[Text_Index];
84  int NT2 = New_Texture[Text_Index + 1];
85  int NT3 = New_Texture[Text_Index + 2];
86 
87  return std::tuple<int, int, int>(NT1, NT2, NT3);
88 }
89 
90 //===================================================
91 // PCL_Conversion
92 // - Function is utilized to fill a point cloud
93 // object with depth and RGB data from a single
94 // frame captured using the Realsense.
95 //===================================================
97 
98  // Object Declaration (Point Cloud)
99  cloud_pointer cloud(new point_cloud);
100 
101  // Declare Tuple for RGB value Storage (<t0>, <t1>, <t2>)
102  std::tuple<uint8_t, uint8_t, uint8_t> RGB_Color;
103 
104  //================================
105  // PCL Cloud Object Configuration
106  //================================
107  // Convert data captured from Realsense camera to Point Cloud
108  auto sp = points.get_profile().as<rs2::video_stream_profile>();
109 
110  cloud->width = static_cast<uint32_t>( sp.width() );
111  cloud->height = static_cast<uint32_t>( sp.height() );
112  cloud->is_dense = false;
113  cloud->points.resize( points.size() );
114 
115  auto Texture_Coord = points.get_texture_coordinates();
116  auto Vertex = points.get_vertices();
117 
118  // Iterating through all points and setting XYZ coordinates
119  // and RGB values
120  for (int i = 0; i < points.size(); i++)
121  {
122  //===================================
123  // Mapping Depth Coordinates
124  // - Depth data stored as XYZ values
125  //===================================
126  cloud->points[i].x = Vertex[i].x;
127  cloud->points[i].y = Vertex[i].y;
128  cloud->points[i].z = Vertex[i].z;
129 
130  // Obtain color texture for specific point
131  RGB_Color = RGB_Texture(color, Texture_Coord[i]);
132 
133  // Mapping Color (BGR due to Camera Model)
134  cloud->points[i].r = get<2>(RGB_Color); // Reference tuple<2>
135  cloud->points[i].g = get<1>(RGB_Color); // Reference tuple<1>
136  cloud->points[i].b = get<0>(RGB_Color); // Reference tuple<0>
137 
138  }
139 
140  return cloud; // PCL RGB Point Cloud generated
141 }
142 
143 int main() try
144 {
145 
146  //======================
147  // Variable Declaration
148  //======================
149  bool captureLoop = true; // Loop control for generating point clouds
150 
151  //====================
152  // Object Declaration
153  //====================
154  pcl::PointCloud<pcl::PointXYZRGB>::Ptr newCloud (new pcl::PointCloud<pcl::PointXYZRGB>);
156 
157  // Declare pointcloud object, for calculating pointclouds and texture mappings
159 
160  // Declare RealSense pipeline, encapsulating the actual device and sensors
162 
163  // Create a configuration for configuring the pipeline with a non default profile
165 
166  //======================
167  // Stream configuration with parameters resolved internally. See enable_stream() overloads for extended usage
168  //======================
172 
173  rs2::pipeline_profile selection = pipe.start(cfg);
174 
175  rs2::device selected_device = selection.get_device();
176  auto depth_sensor = selected_device.first<rs2::depth_sensor>();
177 
179  {
180  depth_sensor.set_option(RS2_OPTION_EMITTER_ENABLED, 1.f); // Enable emitter
181  pipe.wait_for_frames();
182  depth_sensor.set_option(RS2_OPTION_EMITTER_ENABLED, 0.f); // Disable emitter
183  }
184 
185  if (depth_sensor.supports(RS2_OPTION_LASER_POWER))
186  {
187  // Query min and max values:
188  auto range = depth_sensor.get_option_range(RS2_OPTION_LASER_POWER);
189  depth_sensor.set_option(RS2_OPTION_LASER_POWER, range.max); // Set max power
190  sleep(1);
191  depth_sensor.set_option(RS2_OPTION_LASER_POWER, 0.f); // Disable laser
192  }
193 
194  // Begin Stream with default configs
195 
196  // Loop and take frame captures upon user input
197  while(captureLoop == true) {
198 
199  // Set loop flag based on user input
200  captureLoop = userInput();
201  if (captureLoop == false) { break; }
202 
203 
204  // Wait for frames from the camera to settle
205  for (int i = 0; i < 30; i++) {
206  auto frames = pipe.wait_for_frames(); //Drop several frames for auto-exposure
207  }
208 
209  // Capture a single frame and obtain depth + RGB values from it
210  auto frames = pipe.wait_for_frames();
211  auto depth = frames.get_depth_frame();
212  auto RGB = frames.get_color_frame();
213 
214  // Map Color texture to each point
215  pc.map_to(RGB);
216 
217  // Generate Point Cloud
218  auto points = pc.calculate(depth);
219 
220  // Convert generated Point Cloud to PCL Formatting
221  cloud_pointer cloud = PCL_Conversion(points, RGB);
222 
223  //========================================
224  // Filter PointCloud (PassThrough Method)
225  //========================================
226  pcl::PassThrough<pcl::PointXYZRGB> Cloud_Filter; // Create the filtering object
227  Cloud_Filter.setInputCloud (cloud); // Input generated cloud to filter
228  Cloud_Filter.setFilterFieldName ("z"); // Set field name to Z-coordinate
229  Cloud_Filter.setFilterLimits (0.0, 1.0); // Set accepted interval values
230  Cloud_Filter.filter (*newCloud); // Filtered Cloud Outputted
231 
232  cloudFile = "Captured_Frame" + to_string(i) + ".pcd";
233 
234  //==============================
235  // Write PC to .pcd File Format
236  //==============================
237  // Take Cloud Data and write to .PCD File Format
238  cout << "Generating PCD Point Cloud File... " << endl;
239  pcl::io::savePCDFileASCII(cloudFile, *cloud); // Input cloud to be saved to .pcd
240  cout << cloudFile << " successfully generated. " << endl;
241 
242  //Load generated PCD file for viewing
243  Load_PCDFile();
244  i++; // Increment File Name
245  }//End-while
246 
247 
248  cout << "Exiting Program... " << endl;
249  return EXIT_SUCCESS;
250 }
251 catch (const rs2::error & e)
252 {
253  std::cerr << "RealSense error calling " << e.get_failed_function() << "(" << e.get_failed_args() << "):\n " << e.what() << std::endl;
254  return EXIT_FAILURE;
255 }
256 catch (const std::exception & e)
257 {
258  std::cerr << e.what() << std::endl;
259  return EXIT_FAILURE;
260 }
261 
262 
263 void Load_PCDFile(void)
264 {
265  string openFileName;
266 
267  // Generate object to store cloud in .pcd file
268  pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloudView (new pcl::PointCloud<pcl::PointXYZRGB>);
269 
270  openFileName = "Captured_Frame" + to_string(i) + ".pcd";
271  pcl::io::loadPCDFile (openFileName, *cloudView); // Load .pcd File
272 
273  //==========================
274  // Pointcloud Visualization
275  //==========================
276  // Create viewer object titled "Captured Frame"
277  boost::shared_ptr<pcl::visualization::PCLVisualizer> viewer (new pcl::visualization::PCLVisualizer ("Captured Frame"));
278 
279  // Set background of viewer to black
280  viewer->setBackgroundColor (0, 0, 0);
281  // Add generated point cloud and identify with string "Cloud"
282  viewer->addPointCloud<pcl::PointXYZRGB> (cloudView, "Cloud");
283  // Default size for rendered points
284  viewer->setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "Cloud");
285  // Viewer Properties
286  viewer->initCameraParameters(); // Camera Parameters for ease of viewing
287 
288  cout << endl;
289  cout << "Press [Q] in viewer to continue. " << endl;
290 
291  viewer->spin(); // Allow user to rotate point cloud and view it
292 
293  // Note: No method to close PC visualizer, pressing Q to continue software flow only solution.
294 
295 
296 }
297 //========================================
298 // userInput
299 // - Prompts user for a char to
300 // test for decision making.
301 // [y|Y] - Capture frame and save as .pcd
302 // [n|N] - Exit program
303 //========================================
304 bool userInput(void){
305 
306  bool setLoopFlag;
307  bool inputCheck = false;
308  char takeFrame; // Utilize to trigger frame capture from key press ('t')
309  do {
310 
311  // Prompt User to execute frame capture algorithm
312  cout << endl;
313  cout << "Generate a Point Cloud? [y/n] ";
314  cin >> takeFrame;
315  cout << endl;
316  // Condition [Y] - Capture frame, store in PCL object and display
317  if (takeFrame == 'y' || takeFrame == 'Y') {
318  setLoopFlag = true;
319  inputCheck = true;
320  takeFrame = 0;
321  }
322  // Condition [N] - Exit Loop and close program
323  else if (takeFrame == 'n' || takeFrame == 'N') {
324  setLoopFlag = false;
325  inputCheck = true;
326  takeFrame = 0;
327  }
328  // Invalid Input, prompt user again.
329  else {
330  inputCheck = false;
331  cout << "Invalid Input." << endl;
332  takeFrame = 0;
333  }
334  } while(inputCheck == false);
335 
336  return setLoopFlag;
337 }
pcl::PointCloud< RGB_Cloud > point_cloud
frameset wait_for_frames(unsigned int timeout_ms=RS2_DEFAULT_TIMEOUT) const
std::tuple< int, int, int > RGB_Texture(rs2::video_frame texture, rs2::texture_coordinate Texture_XY)
GLfloat x
Definition: particles.c:73
GLfloat y
Definition: particles.c:73
GLuint color
stream_profile get_profile() const
Definition: rs_frame.hpp:557
bool userInput(void)
string prevCloudFile
int get_bytes_per_pixel() const
Definition: rs_frame.hpp:707
GLint GLint GLsizei GLsizei GLsizei depth
const void * get_data() const
Definition: rs_frame.hpp:545
void map_to(frame mapped)
unsigned char uint8_t
Definition: stdint.h:78
e
Definition: rmse.py:177
const texture_coordinate * get_texture_coordinates() const
Definition: rs_frame.hpp:792
The texture class.
Definition: example.hpp:402
size_t size() const
Definition: rs_frame.hpp:800
const std::string & get_failed_args() const
Definition: rs_types.hpp:117
GLdouble f
string cloudFile
pcl::PointXYZRGB RGB_Cloud
std::ostream & cout()
GLsizei const GLuint const GLintptr const GLsizei * strides
Definition: glext.h:2584
unsigned int uint32_t
Definition: stdint.h:80
int main()
points calculate(frame depth) const
GLint GLsizei GLsizei height
const vertex * get_vertices() const
Definition: rs_frame.hpp:767
cloud_pointer PCL_Conversion(const rs2::points &points, const rs2::video_frame &color)
void enable_stream(rs2_stream stream_type, int stream_index, int width, int height, rs2_format format=RS2_FORMAT_ANY, int framerate=0)
device get_device() const
Definition: rs_pipeline.hpp:83
GLfloat z
Definition: particles.c:73
point_cloud::Ptr cloud_pointer
int get_height() const
Definition: rs_frame.hpp:671
int min(int a, int b)
Definition: lz4s.c:73
void Load_PCDFile(void)
void cloudViewer(void)
std::ostream & cerr()
T first() const
Definition: rs_device.hpp:52
GLsizei range
int i
pipeline_profile start()
int get_stride_in_bytes() const
Definition: rs_frame.hpp:683
point_cloud::Ptr prevCloud
int get_width() const
Definition: rs_frame.hpp:659
const std::string & get_failed_function() const
Definition: rs_types.hpp:112
GLint GLsizei width
GLdouble GLdouble GLint GLint const GLdouble * points
std::string to_string(T value)


librealsense2
Author(s): Sergey Dorodnicov , Doron Hirshberg , Mark Horn , Reagan Lopez , Itay Carpis
autogenerated on Mon May 3 2021 02:47:40