Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Enhance frame::get_timestamp() documentation #4739

Merged
merged 1 commit into from
Aug 27, 2019
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
19 changes: 18 additions & 1 deletion include/librealsense2/hpp/rs_frame.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -422,7 +422,24 @@ namespace rs2

/**
* retrieve the time at which the frame was captured
* \return the timestamp of the frame, in milliseconds since the device was started
* During the frame's lifetime it receives timestamps both at the device and host levels.
* The different timestamps are gathered and managed under the frame's Metadata attributes.
* Chronologically the list of timestamps comprises of:
* SENSOR_TIMESTAMP - Device clock. For video sensors designates the middle of exposure. Requires metadata support.
* FRAME_TIMESTAMP - Device clock. Stamped at the beginning of frame readout and transfer. Requires metadata support.
* BACKEND_TIMESTAMP - Host (EPOCH) clock in Kernel space. Frame transfer from USB Controller to the USB Driver.
* TIME_OF_ARRIVAL - Host (EPOCH) clock in User space. Frame transfer from the USB Driver to Librealsense.
*
* During runtime the SDK dynamically selects the most correct representaion, based on both device and host capabilities:
* In case the frame metadata is not configured:
* - The function call provides the TIME_OF_ARRIVAL stamp.
* In case the metadata is available the function returns:
* - `HW Timestamp` (SENSOR_TIMESTAMP), or
* - `Global Timestamp` Host-corrected derivative of `HW Timestamp` required for multi-sensor/device synchronization
* - The user can select between the unmodified and the host-calculated Hardware Timestamp by toggling
* the `RS2_OPTION_GLOBAL_TIME_ENABLED` option.
* To query which of the three alternatives is active use `get_frame_timestamp_domain()` function call
* \return the timestamp of the frame, in milliseconds according to the elaborated flow
*/
double get_timestamp() const
{
Expand Down