Public Member Functions | Private Member Functions | List of all members
rs2::tm2 Class Reference

#include <rs_device.hpp>

Inheritance diagram for rs2::tm2:
Inheritance graph
[legend]

Public Member Functions

void connect_controller (const std::array< uint8_t, 6 > &mac_addr)
 
void disable_loopback ()
 
void disconnect_controller (int id)
 
void enable_loopback (const std::string &from_file)
 
bool is_loopback_enabled () const
 
void set_extrinsics (rs2_stream from_stream, int from_id, rs2_stream to_stream, int to_id, rs2_extrinsics &extrinsics)
 
void set_intrinsics (int fisheye_sensor_id, const rs2_intrinsics &intrinsics)
 
void set_motion_device_intrinsics (rs2_stream stream_type, const rs2_motion_device_intrinsic &motion_intriniscs)
 
 tm2 (device d)
 
- Public Member Functions inherited from rs2::calibrated_device
 calibrated_device (device d)
 
void reset_to_factory_calibration ()
 
void write_calibration () const
 
- Public Member Functions inherited from rs2::device
template<class T >
as () const
 
 device ()
 
 device (std::shared_ptr< rs2_device > dev)
 
template<class T >
first () const
 
const std::shared_ptr< rs2_device > & get () const
 
const char * get_info (rs2_camera_info info) const
 
void hardware_reset ()
 
template<class T >
bool is () const
 
 operator bool () const
 
 operator std::shared_ptr< rs2_device > ()
 
deviceoperator= (const std::shared_ptr< rs2_device > dev)
 
deviceoperator= (const device &dev)
 
std::vector< sensorquery_sensors () const
 
bool supports (rs2_camera_info info) const
 
virtual ~device ()
 

Private Member Functions

std::pair< sensor, stream_profileget_sensor_profile (rs2_stream stream_type, int stream_index)
 

Additional Inherited Members

- Protected Attributes inherited from rs2::device
std::shared_ptr< rs2_device_dev
 

Detailed Description

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:

Definition at line 787 of file rs_device.hpp.

Constructor & Destructor Documentation

rs2::tm2::tm2 ( device  d)
inline

Definition at line 790 of file rs_device.hpp.

Member Function Documentation

void rs2::tm2::connect_controller ( const std::array< uint8_t, 6 > &  mac_addr)
inline

Connects to a given tm2 controller

Parameters
[in]mac_addrThe MAC address of the desired controller

Definition at line 838 of file rs_device.hpp.

void rs2::tm2::disable_loopback ( )
inline

Restores the given device into normal operation mode

Definition at line 815 of file rs_device.hpp.

void rs2::tm2::disconnect_controller ( int  id)
inline

Disconnects a given tm2 controller

Parameters
[in]idThe ID of the desired controller

Definition at line 849 of file rs_device.hpp.

void rs2::tm2::enable_loopback ( const std::string from_file)
inline

Enter the given device into loopback operation mode that uses the given file as input for raw data

Parameters
[in]from_filePath to bag file with raw data for loopback

Definition at line 805 of file rs_device.hpp.

std::pair<sensor, stream_profile> rs2::tm2::get_sensor_profile ( rs2_stream  stream_type,
int  stream_index 
)
inlineprivate

Definition at line 901 of file rs_device.hpp.

bool rs2::tm2::is_loopback_enabled ( ) const
inline

Checks if the device is in loopback mode or not

Returns
true if the device is in loopback operation mode

Definition at line 826 of file rs_device.hpp.

void rs2::tm2::set_extrinsics ( rs2_stream  from_stream,
int  from_id,
rs2_stream  to_stream,
int  to_id,
rs2_extrinsics extrinsics 
)
inline

Set tm2 camera extrinsics

Parameters
[in]from_streamonly support RS2_STREAM_FISHEYE
[in]from_idonly support left fisheye = 1
[in]to_streamonly support RS2_STREAM_FISHEYE
[in]to_idonly support right fisheye = 2
[in]extrinsicsextrinsics value to be written to the device

Definition at line 877 of file rs_device.hpp.

void rs2::tm2::set_intrinsics ( int  fisheye_sensor_id,
const rs2_intrinsics intrinsics 
)
inline

Set tm2 camera intrinsics

Parameters
[in]fisheye_senor_idThe ID of the fisheye sensor
[in]intrinsicsvalue to be written to the device

Definition at line 861 of file rs_device.hpp.

void rs2::tm2::set_motion_device_intrinsics ( rs2_stream  stream_type,
const rs2_motion_device_intrinsic motion_intriniscs 
)
inline

Set tm2 motion device intrinsics

Parameters
[in]stream_typestream type of the motion device
[in]motion_intriniscsintrinsics value to be written to the device

Definition at line 891 of file rs_device.hpp.


The documentation for this class was generated from the following file:


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