Intel® RealSense™ Cross Platform API
Intel Realsense Cross-platform API
|
#include <rs_device.hpp>
Public Member Functions | |
tm2 (device d) | |
void | enable_loopback (const std::string &from_file) |
void | disable_loopback () |
bool | is_loopback_enabled () const |
void | connect_controller (const std::array< uint8_t, 6 > &mac_addr) |
void | disconnect_controller (int id) |
void | set_intrinsics (int fisheye_sensor_id, const rs2_intrinsics &intrinsics) |
void | set_extrinsics (rs2_stream from_stream, int from_id, rs2_stream to_stream, int to_id, rs2_extrinsics &extrinsics) |
void | set_motion_device_intrinsics (rs2_stream stream_type, const rs2_motion_device_intrinsic &motion_intriniscs) |
![]() | |
calibrated_device (device d) | |
void | write_calibration () const |
void | reset_to_factory_calibration () |
![]() | |
std::vector< sensor > | query_sensors () const |
template<class T > | |
T | first () const |
bool | supports (rs2_camera_info info) const |
const char * | get_info (rs2_camera_info info) const |
void | hardware_reset () |
device & | operator= (const std::shared_ptr< rs2_device > dev) |
device & | operator= (const device &dev) |
device () | |
operator bool () const | |
const std::shared_ptr< rs2_device > & | get () const |
template<class T > | |
bool | is () const |
template<class T > | |
T | as () const |
virtual | ~device () |
operator std::shared_ptr< rs2_device > () | |
device (std::shared_ptr< rs2_device > dev) | |
Additional Inherited Members | |
![]() | |
std::shared_ptr< rs2_device > | _dev |
The tm2 class is an interface for T2XX devices, such as T265.
For T265, it provides RS2_STREAM_FISHEYE (2), RS2_STREAM_GYRO, RS2_STREAM_ACCEL, and RS2_STREAM_POSE streams, and contains the following sensors:
|
inline |
|
inline |
Connects to a given tm2 controller
[in] | mac_addr | The MAC address of the desired controller |
|
inline |
Restores the given device into normal operation mode
|
inline |
Disconnects a given tm2 controller
[in] | id | The ID of the desired controller |
|
inline |
Enter the given device into loopback operation mode that uses the given file as input for raw data
[in] | from_file | Path to bag file with raw data for loopback |
|
inline |
Checks if the device is in loopback mode or not
|
inline |
Set tm2 camera extrinsics
[in] | from_stream | only support RS2_STREAM_FISHEYE |
[in] | from_id | only support left fisheye = 1 |
[in] | to_stream | only support RS2_STREAM_FISHEYE |
[in] | to_id | only support right fisheye = 2 |
[in] | extrinsics | extrinsics value to be written to the device |
|
inline |
Set tm2 camera intrinsics
[in] | fisheye_senor_id | The ID of the fisheye sensor |
[in] | intrinsics | value to be written to the device |
|
inline |
Set tm2 motion device intrinsics
[in] | stream_type | stream type of the motion device |
[in] | motion_intriniscs | intrinsics value to be written to the device |