rs_record_playback.hpp
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 #ifndef LIBREALSENSE_RS2_RECORD_PLAYBACK_HPP
5 #define LIBREALSENSE_RS2_RECORD_PLAYBACK_HPP
6 
7 #include "rs_types.hpp"
8 #include "rs_device.hpp"
9 
10 namespace rs2
11 {
12  template<class T>
14  {
16  public:
17  explicit status_changed_callback(T on_status_changed) : on_status_changed_function(on_status_changed) {}
18 
20  {
22  }
23 
24  void release() override { delete this; }
25  };
26 
27  class playback : public device
28  {
29  public:
31 
37  void pause()
38  {
39  rs2_error* e = nullptr;
40  rs2_playback_device_pause(_dev.get(), &e);
41  error::handle(e);
42  }
43 
48  void resume()
49  {
50  rs2_error* e = nullptr;
51  rs2_playback_device_resume(_dev.get(), &e);
52  error::handle(e);
53  }
54 
60  {
61  return m_file; //cached in construction
62  }
63 
69  {
70  rs2_error* e = nullptr;
71  uint64_t pos = rs2_playback_get_position(_dev.get(), &e);
72  error::handle(e);
73  return pos;
74  }
75 
81  {
82  rs2_error* e = nullptr;
84  error::handle(e);
85  return duration;
86  }
87 
93  {
94  rs2_error* e = nullptr;
95  rs2_playback_seek(_dev.get(), time.count(), &e);
96  error::handle(e);
97  }
98 
103  bool is_real_time() const
104  {
105  rs2_error* e = nullptr;
106  bool real_time = rs2_playback_device_is_real_time(_dev.get(), &e) != 0;
107  error::handle(e);
108  return real_time;
109  }
110 
122  void set_real_time(bool real_time) const
123  {
124  rs2_error* e = nullptr;
125  rs2_playback_device_set_real_time(_dev.get(), (real_time ? 1 : 0), &e);
126  error::handle(e);
127  }
128 
133  void set_playback_speed(float speed) const
134  {
135  rs2_error* e = nullptr;
136  rs2_playback_device_set_playback_speed(_dev.get(), speed, &e);
137  error::handle(e);
138  }
139 
152  template <typename T>
154  {
155  rs2_error* e = nullptr;
157  error::handle(e);
158  }
159 
165  {
166  rs2_error* e = nullptr;
168  error::handle(e);
169  return sts;
170  }
171 
176  void stop()
177  {
178  rs2_error* e = nullptr;
179  rs2_playback_device_stop(_dev.get(), &e);
180  error::handle(e);
181  }
182  protected:
183  friend context;
184  explicit playback(std::shared_ptr<rs2_device> dev) : device(dev)
185  {
186  rs2_error* e = nullptr;
187  if(rs2_is_device_extendable_to(_dev.get(), RS2_EXTENSION_PLAYBACK, &e) == 0 && !e)
188  {
189  _dev.reset();
190  }
191  error::handle(e);
192 
193  if(_dev)
194  {
195  e = nullptr;
196  m_file = rs2_playback_device_get_file_path(_dev.get(), &e);
197  error::handle(e);
198  }
199  }
200  private:
202  };
203  class recorder : public device
204  {
205  public:
207 
214  {
215  rs2_error* e = nullptr;
216  _dev = std::shared_ptr<rs2_device>(
217  rs2_create_record_device(dev.get().get(), file.c_str(), &e),
220  }
221 
228  recorder(const std::string& file, rs2::device dev, bool compression_enabled)
229  {
230  rs2_error* e = nullptr;
231  _dev = std::shared_ptr<rs2_device>(
232  rs2_create_record_device_ex(dev.get().get(), file.c_str(), compression_enabled, &e),
235  }
236 
237 
241  void pause()
242  {
243  rs2_error* e = nullptr;
244  rs2_record_device_pause(_dev.get(), &e);
245  error::handle(e);
246  }
247 
251  void resume()
252  {
253  rs2_error* e = nullptr;
254  rs2_record_device_resume(_dev.get(), &e);
255  error::handle(e);
256  }
257 
263  {
264  rs2_error* e = nullptr;
266  error::handle(e);
267  return filename;
268  }
269  protected:
270  explicit recorder(std::shared_ptr<rs2_device> dev) : device(dev)
271  {
272  rs2_error* e = nullptr;
273  if (rs2_is_device_extendable_to(_dev.get(), RS2_EXTENSION_RECORD, &e) == 0 && !e)
274  {
275  _dev.reset();
276  }
277  error::handle(e);
278  }
279  };
280 }
281 #endif // LIBREALSENSE_RS2_RECORD_PLAYBACK_HPP
const char * rs2_playback_device_get_file_path(const rs2_device *device, rs2_error **error)
Definition: rs.cpp:1556
void on_playback_status_changed(rs2_playback_status status) override
bool is_real_time() const
void seek(std::chrono::nanoseconds time)
const std::shared_ptr< rs2_device > & get() const
Definition: rs_device.hpp:116
void rs2_playback_seek(const rs2_device *device, long long int time, rs2_error **error)
Definition: rs.cpp:1572
void rs2_delete_device(rs2_device *device)
Definition: rs.cpp:301
void rs2_playback_device_set_status_changed_callback(const rs2_device *device, rs2_playback_status_changed_callback *callback, rs2_error **error)
Definition: rs.cpp:1621
void rs2_record_device_pause(const rs2_device *device, rs2_error **error)
Definition: rs.cpp:1679
int rs2_playback_device_is_real_time(const rs2_device *device, rs2_error **error)
Definition: rs.cpp:1613
void rs2_playback_device_pause(const rs2_device *device, rs2_error **error)
Definition: rs.cpp:1597
Definition: cah-model.h:10
GLsizei const GLchar *const * string
d
Definition: rmse.py:171
e
Definition: rmse.py:177
rs2_device * rs2_create_record_device_ex(const rs2_device *device, const char *file, int compression_enabled, rs2_error **error)
Definition: rs.cpp:1666
status
Defines return codes that SDK interfaces use. Negative values indicate errors, a zero value indicates...
std::string filename() const
void rs2_playback_device_stop(const rs2_device *device, rs2_error **error)
Definition: rs.cpp:1648
unsigned long long int rs2_playback_get_position(const rs2_device *device, rs2_error **error)
Definition: rs.cpp:1581
void rs2_record_device_resume(const rs2_device *device, rs2_error **error)
Definition: rs.cpp:1687
void set_playback_speed(float speed) const
int rs2_is_device_extendable_to(const rs2_device *device, rs2_extension extension, rs2_error **error)
Definition: rs.cpp:1425
playback(std::shared_ptr< rs2_device > dev)
rs2_playback_status
def callback(frame)
Definition: t265_stereo.py:91
unsigned __int64 uint64_t
Definition: stdint.h:90
BOOST_DEDUCED_TYPENAME optional< T >::reference_const_type get(optional< T > const &opt)
recorder(std::shared_ptr< rs2_device > dev)
unsigned long long int rs2_playback_get_duration(const rs2_device *device, rs2_error **error)
Definition: rs.cpp:1564
static void handle(rs2_error *e)
Definition: rs_types.hpp:144
uint64_t get_position() const
recorder(const std::string &file, rs2::device dev, bool compression_enabled)
std::chrono::duration< uint64_t, std::nano > nanoseconds
status_changed_callback(T on_status_changed)
rs2_playback_status current_status() const
std::chrono::nanoseconds get_duration() const
void set_real_time(bool real_time) const
std::string file_name() const
rs2_device * rs2_create_record_device(const rs2_device *device, const char *file, rs2_error **error)
Definition: rs.cpp:1656
typename::boost::move_detail::remove_reference< T >::type && move(T &&t) BOOST_NOEXCEPT
float rs2_vector::* pos
rs2_playback_status rs2_playback_device_get_current_status(const rs2_device *device, rs2_error **error)
Definition: rs.cpp:1632
const char * rs2_record_device_filename(const rs2_device *device, rs2_error **error)
Definition: rs.cpp:1695
void rs2_playback_device_resume(const rs2_device *device, rs2_error **error)
Definition: rs.cpp:1589
void rs2_playback_device_set_real_time(const rs2_device *device, int real_time, rs2_error **error)
Definition: rs.cpp:1605
void rs2_playback_device_set_playback_speed(const rs2_device *device, float speed, rs2_error **error)
Definition: rs.cpp:1640
recorder(const std::string &file, rs2::device dev)
void set_status_changed_callback(T callback)


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