pyrs_frame.cpp
Go to the documentation of this file.
1 /* License: Apache 2.0. See LICENSE file in root directory.
2 Copyright(c) 2017 Intel Corporation. All Rights Reserved. */
3 
4 #include "python.hpp"
5 #include "../include/librealsense2/rs.hpp"
6 
7 void init_frame(py::module &m) {
8  py::class_<BufData> BufData_py(m, "BufData", py::buffer_protocol());
9  BufData_py.def_buffer([](BufData& self)
10  { return py::buffer_info(
11  self._ptr,
12  self._itemsize,
13  self._format,
14  self._ndim,
15  self._shape,
16  self._strides); }
17  );
18 
19  // Helper function for supporting python's buffer protocol
20  auto get_frame_data = [](const rs2::frame& self) -> BufData
21  {
22  if (auto vf = self.as<rs2::video_frame>()) {
23  std::map<size_t, std::string> bytes_per_pixel_to_format = { { 1, std::string("@B") },{ 2, std::string("@H") },{ 3, std::string("@I") },{ 4, std::string("@I") } };
24  switch (vf.get_profile().format()) {
26  return BufData(const_cast<void*>(vf.get_data()), 1, bytes_per_pixel_to_format[1], 3,
27  { static_cast<size_t>(vf.get_height()), static_cast<size_t>(vf.get_width()), 3 },
28  { static_cast<size_t>(vf.get_stride_in_bytes()), static_cast<size_t>(vf.get_bytes_per_pixel()), 1 });
29  break;
31  return BufData(const_cast<void*>(vf.get_data()), 1, bytes_per_pixel_to_format[1], 3,
32  { static_cast<size_t>(vf.get_height()), static_cast<size_t>(vf.get_width()), 4 },
33  { static_cast<size_t>(vf.get_stride_in_bytes()), static_cast<size_t>(vf.get_bytes_per_pixel()), 1 });
34  break;
35  default:
36  return BufData(const_cast<void*>(vf.get_data()), static_cast<size_t>(vf.get_bytes_per_pixel()), bytes_per_pixel_to_format[vf.get_bytes_per_pixel()], 2,
37  { static_cast<size_t>(vf.get_height()), static_cast<size_t>(vf.get_width()) },
38  { static_cast<size_t>(vf.get_stride_in_bytes()), static_cast<size_t>(vf.get_bytes_per_pixel()) });
39  }
40  }
41  else
42  return BufData(const_cast<void*>(self.get_data()), 1, std::string("@B"), 0); };
43 
44  /* rs_frame.hpp */
45  py::class_<rs2::stream_profile> stream_profile(m, "stream_profile", "Stores details about the profile of a stream.");
46  stream_profile.def(py::init<>())
47  .def("stream_index", &rs2::stream_profile::stream_index, "The stream's index")
48  .def("stream_type", &rs2::stream_profile::stream_type, "The stream's type")
49  .def("format", &rs2::stream_profile::format, "The stream's format")
50  .def("fps", &rs2::stream_profile::fps, "The streams framerate")
51  .def("unique_id", &rs2::stream_profile::unique_id, "Unique index assigned whent the stream was created")
52  .def("clone", &rs2::stream_profile::clone, "Clone the current profile and change the type, index and format to input parameters", "type"_a, "index"_a, "format"_a)
53  .def(BIND_DOWNCAST(stream_profile, stream_profile))
54  .def(BIND_DOWNCAST(stream_profile, video_stream_profile))
55  .def(BIND_DOWNCAST(stream_profile, motion_stream_profile))
56  .def("stream_name", &rs2::stream_profile::stream_name, "The stream's human-readable name.")
57  .def("is_default", &rs2::stream_profile::is_default, "Checks if the stream profile is marked/assigned as default, "
58  "meaning that the profile will be selected when the user requests stream configuration using wildcards.")
59  .def("__nonzero__", &rs2::stream_profile::operator bool, "Checks if the profile is valid") // Called to implement truth value testing in Python 2
60  .def("__bool__", &rs2::stream_profile::operator bool, "Checks if the profile is valid") // Called to implement truth value testing in Python 3
61 
62  .def("get_extrinsics_to", &rs2::stream_profile::get_extrinsics_to, "Get the extrinsic transformation between two profiles (representing physical sensors)", "to"_a)
63  .def("register_extrinsics_to", &rs2::stream_profile::register_extrinsics_to, "Assign extrinsic transformation parameters "
64  "to a specific profile (sensor). The extrinsic information is generally available as part of the camera calibration, "
65  "and librealsense is responsible for retrieving and assigning these parameters where appropriate. This specific function "
66  "is intended for synthetic/mock-up (software) devices for which the parameters are produced and injected by the user.", "to"_a, "extrinsics"_a)
67  .def("__repr__", [](const rs2::stream_profile& self) {
68  std::stringstream ss;
69  if (auto vf = self.as<rs2::video_stream_profile>())
70  {
71  ss << "<" SNAME ".video_stream_profile: "
72  << vf.stream_type() << "(" << vf.stream_index() << ") " << vf.width()
73  << "x" << vf.height() << " @ " << vf.fps() << "fps "
74  << vf.format() << ">";
75  }
76  else
77  {
78  ss << "<" SNAME ".stream_profile: " << self.stream_type() << "(" << self.stream_index()
79  << ") @ " << self.fps() << "fps " << self.format() << ">";
80  }
81  return ss.str();
82  });
83 
84  py::class_<rs2::video_stream_profile, rs2::stream_profile> video_stream_profile(m, "video_stream_profile", "Stream profile instance which contains additional video attributes.");
85  video_stream_profile.def(py::init<const rs2::stream_profile&>(), "sp"_a)
86  .def("width", &rs2::video_stream_profile::width) // No docstring in C++
87  .def("height", &rs2::video_stream_profile::height) // No docstring in C++
88  .def("get_intrinsics", &rs2::video_stream_profile::get_intrinsics, "Get stream profile instrinsics attributes.")
89  .def_property_readonly("intrinsics", &rs2::video_stream_profile::get_intrinsics, "Stream profile instrinsics attributes. Identical to calling get_intrinsics.")
90  .def("__repr__", [](const rs2::video_stream_profile& self) {
91  std::stringstream ss;
92  ss << "<" SNAME ".video_stream_profile: "
93  << self.stream_type() << "(" << self.stream_index() << ") " << self.width()
94  << "x" << self.height() << " @ " << self.fps() << "fps "
95  << self.format() << ">";
96  return ss.str();
97  });
98 
99  py::class_<rs2::motion_stream_profile, rs2::stream_profile> motion_stream_profile(m, "motion_stream_profile", "Stream profile instance which contains IMU-specific intrinsics.");
100  motion_stream_profile.def(py::init<const rs2::stream_profile&>(), "sp"_a)
101  .def("get_motion_intrinsics", &rs2::motion_stream_profile::get_motion_intrinsics, "Returns scale and bias of a motion stream.");
102 
103  py::class_<rs2::pose_stream_profile, rs2::stream_profile> pose_stream_profile(m, "pose_stream_profile", "Stream profile instance with an explicit pose extension type.");
104  pose_stream_profile.def(py::init<const rs2::stream_profile&>(), "sp"_a);
105 
106  py::class_<rs2::filter_interface> filter_interface(m, "filter_interface", "Interface for frame filtering functionality");
107  filter_interface.def("process", &rs2::filter_interface::process, "frame"_a); // No docstring in C++
108 
109  py::class_<rs2::frame> frame(m, "frame", "Base class for multiple frame extensions");
110  frame.def(py::init<>())
111  // .def(py::self = py::self) // can't overload assignment in python
112  .def(py::init<rs2::frame>())
113  .def("swap", &rs2::frame::swap, "Swap the internal frame handle with the one in parameter", "other"_a)
114  .def("__nonzero__", &rs2::frame::operator bool, "check if internal frame handle is valid") // Called to implement truth value testing in Python 2
115  .def("__bool__", &rs2::frame::operator bool, "check if internal frame handle is valid") // Called to implement truth value testing in Python 3
116  .def("get_timestamp", &rs2::frame::get_timestamp, "Retrieve the time at which the frame was captured")
117  .def_property_readonly("timestamp", &rs2::frame::get_timestamp, "Time at which the frame was captured. Identical to calling get_timestamp.")
118  .def("get_frame_timestamp_domain", &rs2::frame::get_frame_timestamp_domain, "Retrieve the timestamp domain.")
119  .def_property_readonly("frame_timestamp_domain", &rs2::frame::get_frame_timestamp_domain, "The timestamp domain. Identical to calling get_frame_timestamp_domain.")
120  .def("get_frame_metadata", &rs2::frame::get_frame_metadata, "Retrieve the current value of a single frame_metadata.", "frame_metadata"_a)
121  .def("supports_frame_metadata", &rs2::frame::supports_frame_metadata, "Determine if the device allows a specific metadata to be queried.", "frame_metadata"_a)
122  .def("get_frame_number", &rs2::frame::get_frame_number, "Retrieve the frame number.")
123  .def_property_readonly("frame_number", &rs2::frame::get_frame_number, "The frame number. Identical to calling get_frame_number.")
124  .def("get_data_size", &rs2::frame::get_data_size, "Retrieve data size from frame handle.")
125  .def("get_data", get_frame_data, "Retrieve data from the frame handle.", py::keep_alive<0, 1>())
126  .def_property_readonly("data", get_frame_data, "Data from the frame handle. Identical to calling get_data.", py::keep_alive<0, 1>())
127  .def("get_profile", &rs2::frame::get_profile, "Retrieve stream profile from frame handle.")
128  .def_property_readonly("profile", &rs2::frame::get_profile, "Stream profile from frame handle. Identical to calling get_profile.")
129  .def("keep", &rs2::frame::keep, "Keep the frame, otherwise if no refernce to the frame, the frame will be released.")
130  .def(BIND_DOWNCAST(frame, frame))
131  .def(BIND_DOWNCAST(frame, points))
132  .def(BIND_DOWNCAST(frame, frameset))
133  .def(BIND_DOWNCAST(frame, video_frame))
134  .def(BIND_DOWNCAST(frame, depth_frame))
135  .def(BIND_DOWNCAST(frame, motion_frame))
136  .def(BIND_DOWNCAST(frame, pose_frame))
137  // No apply_filter?
138  .def( "__repr__", []( const rs2::frame &self )
139  {
140  std::stringstream ss;
141  ss << "<" << SNAME << ".frame";
142  if( auto fs = self.as< rs2::frameset >() )
143  {
144  ss << "set";
145  for( auto sf : fs )
146  ss << " " << rs2_format_to_string( sf.get_profile().format() );
147  }
148  else
149  {
150  ss << " " << rs2_format_to_string( self.get_profile().format() );
151  }
152  ss << " #" << self.get_frame_number();
153  ss << ">";
154  return ss.str();
155  });
156 
157  py::class_<rs2::video_frame, rs2::frame> video_frame(m, "video_frame", "Extends the frame class with additional video related attributes and functions.");
158  video_frame.def(py::init<rs2::frame>())
159  .def("get_width", &rs2::video_frame::get_width, "Returns image width in pixels.")
160  .def_property_readonly("width", &rs2::video_frame::get_width, "Image width in pixels. Identical to calling get_width.")
161  .def("get_height", &rs2::video_frame::get_height, "Returns image height in pixels.")
162  .def_property_readonly("height", &rs2::video_frame::get_height, "Image height in pixels. Identical to calling get_height.")
163  .def("get_stride_in_bytes", &rs2::video_frame::get_stride_in_bytes, "Retrieve frame stride, meaning the actual line width in memory in bytes (not the logical image width).")
164  .def_property_readonly("stride_in_bytes", &rs2::video_frame::get_stride_in_bytes, "Frame stride, meaning the actual line width in memory in bytes (not the logical image width). Identical to calling get_stride_in_bytes.")
165  .def("get_bits_per_pixel", &rs2::video_frame::get_bits_per_pixel, "Retrieve bits per pixel.")
166  .def_property_readonly("bits_per_pixel", &rs2::video_frame::get_bits_per_pixel, "Bits per pixel. Identical to calling get_bits_per_pixel.")
167  .def("get_bytes_per_pixel", &rs2::video_frame::get_bytes_per_pixel, "Retrieve bytes per pixel.")
168  .def_property_readonly("bytes_per_pixel", &rs2::video_frame::get_bytes_per_pixel, "Bytes per pixel. Identical to calling get_bytes_per_pixel.")
169  .def("extract_target_dimensions", [](const rs2::video_frame& self, rs2_calib_target_type target_type)->std::vector<float>
170  {
171  std::vector<float> target_dims;
173  {
174  target_dims.resize(4);
175  self.extract_target_dimensions(RS2_CALIB_TARGET_RECT_GAUSSIAN_DOT_VERTICES, target_dims.data(), 4);
176  }
177  return target_dims;
178  }, "This will calculate the four target dimenson size(s) in millimeter on the specific target.");
179 
180  py::class_<rs2::vertex> vertex(m, "vertex"); // No docstring in C++
181  vertex.def_readwrite("x", &rs2::vertex::x)
182  .def_readwrite("y", &rs2::vertex::y)
183  .def_readwrite("z", &rs2::vertex::z)
184  .def(py::init([]() { return rs2::vertex{}; }))
185  .def(py::init([](float x, float y, float z) { return rs2::vertex{ x,y,z }; }))
186  .def("__repr__", [](const rs2::vertex& v) {
187  std::ostringstream oss;
188  oss << v.x << ", " << v.y << ", " << v.z;
189  return oss.str();
190  });
191 
192  py::class_<rs2::texture_coordinate> texture_coordinate(m, "texture_coordinate"); // No docstring in C++
193  texture_coordinate.def_readwrite("u", &rs2::texture_coordinate::u)
194  .def_readwrite("v", &rs2::texture_coordinate::v)
195  .def(py::init([]() { return rs2::texture_coordinate{}; }))
196  .def(py::init([](float u, float v) { return rs2::texture_coordinate{ u, v }; }))
197  .def("__repr__", [](const rs2::texture_coordinate& t) {
198  std::ostringstream oss;
199  oss << t.u << ", " << t.v;
200  return oss.str();
201  });
202 
203  py::class_<rs2::points, rs2::frame> points(m, "points", "Extends the frame class with additional point cloud related attributes and functions.");
204  points.def(py::init<>())
205  .def(py::init<rs2::frame>())
206  .def("get_vertices", [](rs2::points& self, int dims) {
207  auto verts = const_cast<rs2::vertex*>(self.get_vertices());
208  auto profile = self.get_profile().as<rs2::video_stream_profile>();
209  size_t h = profile.height(), w = profile.width();
210  switch (dims) {
211  case 1:
212  return BufData(verts, sizeof(rs2::vertex), "@fff", self.size());
213  case 2:
214  return BufData(verts, sizeof(float), "@f", 3, self.size());
215  case 3:
216  return BufData(verts, sizeof(float), "@f", 3, { h, w, 3 }, { w*3*sizeof(float), 3*sizeof(float), sizeof(float) });
217  default:
218  throw std::domain_error("dims arg only supports values of 1, 2 or 3");
219  }
220  }, "Retrieve the vertices of the point cloud", py::keep_alive<0, 1>(), "dims"_a=1)
221  .def("get_texture_coordinates", [](rs2::points& self, int dims) {
222  auto tex = const_cast<rs2::texture_coordinate*>(self.get_texture_coordinates());
223  auto profile = self.get_profile().as<rs2::video_stream_profile>();
224  size_t h = profile.height(), w = profile.width();
225  switch (dims) {
226  case 1:
227  return BufData(tex, sizeof(rs2::texture_coordinate), "@ff", self.size());
228  case 2:
229  return BufData(tex, sizeof(float), "@f", 2, self.size());
230  case 3:
231  return BufData(tex, sizeof(float), "@f", 2, { h, w, 2 }, { w*2*sizeof(float), 2*sizeof(float), sizeof(float) });
232  default:
233  throw std::domain_error("dims arg only supports values of 1, 2 or 3");
234  }
235  }, "Retrieve the texture coordinates (uv map) for the point cloud", py::keep_alive<0, 1>(), "dims"_a=1)
236  .def("export_to_ply", &rs2::points::export_to_ply, "Export the point cloud to a PLY file")
237  .def("size", &rs2::points::size); // No docstring in C++
238 
239  py::class_<rs2::depth_frame, rs2::video_frame> depth_frame(m, "depth_frame", "Extends the video_frame class with additional depth related attributes and functions.");
240  depth_frame.def(py::init<rs2::frame>())
241  .def("get_distance", &rs2::depth_frame::get_distance, "x"_a, "y"_a, "Provide the depth in meters at the given pixel")
242  .def("get_units", &rs2::depth_frame::get_units, "Provide the scaling factor to use when converting from get_data() units to meters");
243 
244  // rs2::disparity_frame
245  py::class_<rs2::disparity_frame, rs2::depth_frame> disparity_frame(m, "disparity_frame", "Extends the depth_frame class with additional disparity related attributes and functions.");
246  disparity_frame.def(py::init<rs2::frame>())
247  .def("get_baseline", &rs2::disparity_frame::get_baseline, "Retrieve the distance between the two IR sensors.");
248 
249  py::class_<rs2::motion_frame, rs2::frame> motion_frame(m, "motion_frame", "Extends the frame class with additional motion related attributes and functions");
250  motion_frame.def(py::init<rs2::frame>())
251  .def("get_motion_data", &rs2::motion_frame::get_motion_data, "Retrieve the motion data from IMU sensor.")
252  .def_property_readonly("motion_data", &rs2::motion_frame::get_motion_data, "Motion data from IMU sensor. Identical to calling get_motion_data.");
253 
254  py::class_<rs2::pose_frame, rs2::frame> pose_frame(m, "pose_frame", "Extends the frame class with additional pose related attributes and functions.");
255  pose_frame.def(py::init<rs2::frame>())
256  .def("get_pose_data", &rs2::pose_frame::get_pose_data, "Retrieve the pose data from T2xx position tracking sensor.")
257  .def_property_readonly("pose_data", &rs2::pose_frame::get_pose_data, "Pose data from T2xx position tracking sensor. Identical to calling get_pose_data.");
258 
259  // TODO: Deprecate composite_frame, replace with frameset
260  py::class_<rs2::frameset, rs2::frame> frameset(m, "composite_frame", "Extends the frame class with additional frameset related attributes and functions");
261  frameset.def(py::init<rs2::frame>())
262  .def("first_or_default", &rs2::frameset::first_or_default, "Retrieve the first frame of a specific stream and optionally with a specific format. "
263  "If no frame is found, return an empty frame instance.", "s"_a, "f"_a = RS2_FORMAT_ANY)
264  .def("first", &rs2::frameset::first, "Retrieve the first frame of a specific stream type and optionally with a specific format. "
265  "If no frame is found, an error will be thrown.", "s"_a, "f"_a = RS2_FORMAT_ANY)
266  .def("size", &rs2::frameset::size, "Return the size of the frameset")
267  .def("__len__", &rs2::frameset::size, "Return the size of the frameset")
268  .def("foreach", [](const rs2::frameset& self, std::function<void(rs2::frame)> callable) {
269  self.foreach_rs(callable);
270  }, "Extract internal frame handles from the frameset and invoke the action function", "callable"_a)
271  .def("__getitem__", &rs2::frameset::operator[])
272  .def("get_depth_frame", &rs2::frameset::get_depth_frame, "Retrieve the first depth frame, if no frame is found, return an empty frame instance.")
273  .def("get_color_frame", &rs2::frameset::get_color_frame, "Retrieve the first color frame, if no frame is found, search for the color frame from IR stream. "
274  "If one still can't be found, return an empty frame instance.")
275  .def("get_infrared_frame", &rs2::frameset::get_infrared_frame, "Retrieve the first infrared frame, if no frame is "
276  "found, return an empty frame instance.", "index"_a = 0)
277  .def("get_fisheye_frame", &rs2::frameset::get_fisheye_frame, "Retrieve the fisheye monochrome video frame", "index"_a = 0)
278  .def("get_pose_frame", &rs2::frameset::get_pose_frame, "Retrieve the pose frame", "index"_a = 0)
279  .def("__iter__", [](rs2::frameset& self) {
280  return py::make_iterator(self.begin(), self.end());
281  }, py::keep_alive<0, 1>())
282  .def("__getitem__", [](const rs2::frameset& self, py::slice slice) {
283  size_t start, stop, step, slicelength;
284  if (!slice.compute(self.size(), &start, &stop, &step, &slicelength))
285  throw py::error_already_set();
286  auto *flist = new std::vector<rs2::frame>(slicelength);
287  for (size_t i = 0; i < slicelength; ++i) {
288  (*flist)[i] = self[start];
289  start += step;
290  }
291  return flist;
292  });
294 }
const char * rs2_format_to_string(rs2_format format)
Definition: rs.cpp:1263
GLuint GLuint end
GLint y
rs2_motion_device_intrinsic get_motion_intrinsics() const
Definition: rs_frame.hpp:304
const GLfloat * m
Definition: glext.h:6814
void register_extrinsics_to(const stream_profile &to, rs2_extrinsics extrinsics)
Definition: rs_frame.hpp:162
rs2_metadata_type get_frame_metadata(rs2_frame_metadata_value frame_metadata) const
Definition: rs_frame.hpp:497
rs2_extrinsics get_extrinsics_to(const stream_profile &to) const
Definition: rs_frame.hpp:148
stream_profile get_profile() const
Definition: rs_frame.hpp:557
rs2_calib_target_type
Calibration target type.
Definition: rs_frame.h:74
int get_bytes_per_pixel() const
Definition: rs_frame.hpp:707
float get_units() const
Definition: rs_frame.hpp:845
#define BIND_DOWNCAST(class, downcast)
Definition: python.hpp:33
struct Vertex vertex[VERTEXNUM]
Definition: wave.c:52
bool supports_frame_metadata(rs2_frame_metadata_value frame_metadata) const
Definition: rs_frame.hpp:509
void export_to_ply(const std::string &fname, video_frame texture)
Definition: rs_frame.hpp:780
std::string stream_name() const
Definition: rs_frame.hpp:113
GLdouble GLdouble GLdouble w
GLsizei const GLchar *const * string
GLfloat GLfloat GLfloat GLfloat h
Definition: glext.h:1960
GLdouble GLdouble z
static const textual_icon stop
Definition: model-views.h:225
rs2_pose get_pose_data() const
Definition: rs_frame.hpp:933
depth_frame get_depth_frame() const
Definition: rs_frame.hpp:1006
frame first_or_default(rs2_stream s, rs2_format f=RS2_FORMAT_ANY) const
Definition: rs_frame.hpp:978
GLdouble t
void swap(frame &other)
Definition: rs_frame.hpp:413
size_t size() const
Definition: rs_frame.hpp:800
video_frame get_color_frame() const
Definition: rs_frame.hpp:1015
void init_frame(py::module &m)
Definition: pyrs_frame.cpp:7
not_this_one begin(...)
rs2_vector get_motion_data() const
Definition: rs_frame.hpp:905
frame first(rs2_stream s, rs2_format f=RS2_FORMAT_ANY) const
Definition: rs_frame.hpp:995
video_frame get_fisheye_frame(const size_t index=0) const
Definition: rs_frame.hpp:1054
GLsizeiptr size
pose_frame get_pose_frame(const size_t index=0) const
Definition: rs_frame.hpp:1076
GLdouble x
double get_timestamp() const
Definition: rs_frame.hpp:474
float get_baseline(void) const
Definition: rs_frame.hpp:875
#define SNAME
Definition: pybackend.cpp:27
GLint GLint GLsizei GLint GLenum format
void init(void)
Definition: boing.c:180
GLuint start
bool is_default() const
Definition: rs_frame.hpp:125
void keep()
Definition: rs_frame.hpp:437
int stream_index() const
Definition: rs_frame.hpp:34
rs2_intrinsics get_intrinsics() const
Definition: rs_frame.hpp:238
rs2_format format() const
Definition: rs_frame.hpp:44
float get_distance(int x, int y) const
Definition: rs_frame.hpp:833
virtual rs2::frame process(rs2::frame frame) const =0
rs2_timestamp_domain get_frame_timestamp_domain() const
Definition: rs_frame.hpp:485
int get_height() const
Definition: rs_frame.hpp:671
int get_bits_per_pixel() const
Definition: rs_frame.hpp:695
const int get_data_size() const
Definition: rs_frame.hpp:533
video_frame get_infrared_frame(const size_t index=0) const
Definition: rs_frame.hpp:1032
int i
int unique_id() const
Definition: rs_frame.hpp:54
unsigned long long get_frame_number() const
Definition: rs_frame.hpp:521
int get_stride_in_bytes() const
Definition: rs_frame.hpp:683
size_t size() const
Definition: rs_frame.hpp:1097
rs2_stream stream_type() const
Definition: rs_frame.hpp:39
GLdouble v
stream_profile clone(rs2_stream type, int index, rs2_format format) const
Definition: rs_frame.hpp:63
int get_width() const
Definition: rs_frame.hpp:659
int fps() const
Definition: rs_frame.hpp:49
GLdouble GLdouble GLint GLint const GLdouble * points


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