Class playback
Defined in File rs_record_playback.hpp
Inheritance Relationships
Base Type
public rs2::device
(Class device)
Class Documentation
-
class playback : public rs2::device
Public Functions
-
inline void pause()
Pauses the playback Calling pause() in “Paused” status does nothing If pause() is called while playback status is “Playing” or “Stopped”, the playback will not play until resume() is called
-
inline void resume()
Un-pauses the playback Calling resume() while playback status is “Playing” or “Stopped” does nothing
-
inline std::string file_name() const
Retrieves the name of the playback file
- Returns:
Name of the playback file
-
inline uint64_t get_position() const
Retrieves the current position of the playback in the file in terms of time. Units are expressed in nanoseconds
- Returns:
Current position of the playback in the file in terms of time. Units are expressed in nanoseconds
-
inline std::chrono::nanoseconds get_duration() const
Retrieves the total duration of the file
- Returns:
Total duration of the file
-
inline void seek(std::chrono::nanoseconds time)
Sets the playback to a specified time point of the played data
- Parameters:
time – [in] The time point to which playback should seek, expressed in units of nanoseconds (zero value = start)
-
inline bool is_real_time() const
Indicates if playback is in real time mode or non real time
- Returns:
True iff playback is in real time mode
-
inline void set_real_time(bool real_time) const
Set the playback to work in real time or non real time
In real time mode, playback will play the same way the file was recorded. In real time mode if the application takes too long to handle the callback, frames may be dropped. In non real time mode, playback will wait for each callback to finish handling the data before reading the next frame. In this mode no frames will be dropped, and the application controls the frame rate of the playback (according to the callback handler duration).
- Parameters:
real_time – [in] Indicates if real time is requested, 0 means false, otherwise true
- Returns:
True on successfully setting the requested mode
-
inline void set_playback_speed(float speed) const
Set the playing speed
- Parameters:
speed – [in] Indicates a multiplication of the speed to play (e.g: 1 = normal, 0.5 twice as slow)
-
template<typename T>
inline void set_status_changed_callback(T callback) Start passing frames into user provided callback
Callbacks are invoked from the reading thread, and as such any heavy processing in the callback handler will affect the reading thread and may cause frame drops\ high latency
- Parameters:
callback – [in] Stream callback, can be any callable object accepting rs2::frame Register to receive callback from playback device upon its status changes
callback – [in] A callback handler that will be invoked when the playback status changes, can be any callable object accepting rs2_playback_status
-
inline rs2_playback_status current_status() const
Returns the current state of the playback device
- Returns:
Current state of the playback
-
inline void stop()
Stops the playback, effectively stopping all streaming playback sensors, and resetting the playback.
Protected Functions
Protected Attributes
- friend context
-
inline void pause()