rs-pose-and-image.cpp
Go to the documentation of this file.
1 // License: Apache 2.0. See LICENSE file in root directory.
2 // Copyright(c) 2019 Intel Corporation. All Rights Reserved.
3 #include <librealsense2/rs.hpp>
4 #include <iostream>
5 #include <iomanip>
6 #include <chrono>
7 #include <thread>
8 #include <mutex>
9 
10 int main(int argc, char * argv[]) try
11 {
12  // Declare RealSense pipeline, encapsulating the actual device and sensors
14  // Create a configuration for configuring the pipeline with a non default profile
16  // Add pose stream
18  // Enable both image streams
19  // Note: It is not currently possible to enable only one
22 
23  // Define frame callback
24 
25  // The callback is executed on a sensor thread and can be called simultaneously from multiple sensors
26  // Therefore any modification to common memory should be done under lock
27  std::mutex data_mutex;
28  uint64_t pose_counter = 0;
30  bool first_data = true;
31  auto last_print = std::chrono::system_clock::now();
32  auto callback = [&](const rs2::frame& frame)
33  {
34  std::lock_guard<std::mutex> lock(data_mutex);
35  // Only start measuring time elapsed once we have received the
36  // first piece of data
37  if (first_data) {
38  first_data = false;
39  last_print = std::chrono::system_clock::now();
40  }
41 
42  if (auto fp = frame.as<rs2::pose_frame>()) {
43  pose_counter++;
44  }
45  else if (auto fs = frame.as<rs2::frameset>()) {
46  frame_counter++;
47  }
48 
49  // Print the approximate pose and image rates once per second
51  if (now - last_print >= std::chrono::seconds(1)) {
52  std::cout << "\r" << std::setprecision(0) << std::fixed
53  << "Pose rate: " << pose_counter << " "
54  << "Image rate: " << frame_counter << std::flush;
55  pose_counter = 0;
56  frame_counter = 0;
57  last_print = now;
58  }
59  };
60 
61  // Start streaming through the callback
63 
64  // Sleep this thread until we are done
65  while(true) {
66  std::this_thread::sleep_for(std::chrono::milliseconds(10));
67  }
68 
69  return EXIT_SUCCESS;
70 }
71 catch (const rs2::error & e)
72 {
73  std::cerr << "RealSense error calling " << e.get_failed_function() << "(" << e.get_failed_args() << "):\n " << e.what() << std::endl;
74  return EXIT_FAILURE;
75 }
76 catch (const std::exception& e)
77 {
78  std::cerr << e.what() << std::endl;
79  return EXIT_FAILURE;
80 }
static const textual_icon lock
Definition: model-views.h:218
e
Definition: rmse.py:177
const std::string & get_failed_args() const
Definition: rs_types.hpp:117
std::ostream & cout()
def callback(frame)
Definition: t265_stereo.py:91
unsigned __int64 uint64_t
Definition: stdint.h:90
void enable_stream(rs2_stream stream_type, int stream_index, int width, int height, rs2_format format=RS2_FORMAT_ANY, int framerate=0)
std::ostream & cerr()
pipeline_profile start()
int main(int argc, char *argv[])
const std::string & get_failed_function() const
Definition: rs_types.hpp:112


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