Classes | Namespaces | Macros | Typedefs | Enumerations | Functions | Variables
src/types.h File Reference
#include "../include/librealsense2/hpp/rs_types.hpp"
#include <cmath>
#include <ctime>
#include <stdint.h>
#include <cassert>
#include <cstring>
#include <vector>
#include <sstream>
#include <mutex>
#include <memory>
#include <map>
#include <limits>
#include <algorithm>
#include <condition_variable>
#include <functional>
#include <utility>
#include <iomanip>
#include "backend.h"
#include "concurrency.h"
Include dependency graph for src/types.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

class  librealsense::arithmetic_wraparound< T, S >
 
class  librealsense::backend_exception
 
class  librealsense::big_endian< T >
 
class  librealsense::calibration_validator
 
struct  librealsense::callback_invocation
 
struct  librealsense::callback_invocation_holder
 
class  librealsense::camera_disconnected_exception
 
class  librealsense::devices_changed_callback
 
class  librealsense::devices_changed_callback_internal
 
struct  librealsense::devices_data
 
class  librealsense::firmware_version
 
struct  librealsense::float2
 
struct  librealsense::float3
 
struct  librealsense::float3x3
 
struct  librealsense::float4
 
class  librealsense::frame_callback
 
class  librealsense::frame_continuation
 
struct  std::hash< librealsense::platform::stream_profile >
 
struct  std::hash< librealsense::stream_profile >
 
struct  std::hash< rs2_format >
 
struct  librealsense::hid_data
 
struct  librealsense::hid_device_info
 
struct  librealsense::int2
 
class  librealsense::internal_frame_callback< T >
 
class  librealsense::internal_frame_processor_fptr_callback
 
class  librealsense::invalid_value_exception
 
class  librealsense::io_exception
 
struct  librealsense::isNarrowing< T, S >
 
class  librealsense::lazy< T >
 
class  librealsense::librealsense_exception
 
class  librealsense::linux_backend_exception
 
class  librealsense::not_implemented_exception
 
struct  librealsense::notification
 
class  librealsense::notification_decoder
 
class  librealsense::notifications_callback
 
class  librealsense::notifications_processor
 
class  librealsense::optional_value< T >
 
struct  librealsense::pixel_format_unpacker
 
class  librealsense::polling_device_watcher
 
struct  librealsense::pose
 
class  librealsense::recoverable_exception
 
struct  librealsense::resolution
 
class  librealsense::signal< HostingClass, Args >
 
class  librealsense::small_heap< T, C >
 
class  librealsense::software_device_destruction_callback
 
struct  librealsense::stream_descriptor
 
struct  librealsense::stream_output
 
struct  librealsense::stream_profile
 
struct  librealsense::struct_interface< T, R, W >
 
struct  librealsense::to_string
 
class  librealsense::unique_id
 
class  librealsense::unrecoverable_exception
 
class  librealsense::update_progress_callback
 
struct  librealsense::usb_device_info
 
struct  librealsense::uvc_device_info
 
class  librealsense::windows_backend_exception
 
class  librealsense::wrong_api_call_sequence_exception
 

Namespaces

 librealsense
 
 std
 

Macros

#define _USE_MATH_DEFINES
 
#define LIBREALSENSE_TYPES_H
 
#define LOG_DEBUG(...)   do { ; } while(false)
 
#define LOG_ERROR(...)   do { ; } while(false)
 
#define LOG_FATAL(...)   do { ; } while(false)
 
#define LOG_INFO(...)   do { ; } while(false)
 
#define LOG_WARNING(...)   do { ; } while(false)
 
#define LRS_EXTENSION_API
 
#define PRIVATE_TESTABLE   private
 
#define RS2_ENUM_HELPERS(TYPE, PREFIX)   RS2_ENUM_HELPERS_CUSTOMIZED( TYPE, 0, RS2_##PREFIX##_COUNT - 1 )
 
#define RS2_ENUM_HELPERS_CUSTOMIZED(TYPE, FIRST, LAST)
 
#define UNKNOWN_VALUE   "UNKNOWN"
 

Typedefs

typedef unsigned char byte
 
typedef std::shared_ptr< rs2_calibration_change_callbacklibrealsense::calibration_change_callback_ptr
 
typedef librealsense::small_heap< callback_invocation, 1 > librealsense::callbacks_heap
 
typedef std::function< void(devices_data old, devices_data curr)> librealsense::device_changed_callback
 
typedef std::shared_ptr< rs2_devices_changed_callbacklibrealsense::devices_changed_callback_ptr
 
typedef void(* librealsense::devices_changed_function_ptr) (rs2_device_list *removed, rs2_device_list *added, void *user)
 
typedef float librealsense::float_4[4]
 
typedef void(* librealsense::frame_callback_function_ptr) (rs2_frame *frame, void *user)
 
typedef std::shared_ptr< rs2_frame_callbacklibrealsense::frame_callback_ptr
 
typedef std::shared_ptr< rs2_frame_processor_callbacklibrealsense::frame_processor_callback_ptr
 
using librealsense::internal_callback = std::function< void(rs2_device_list *removed, rs2_device_list *added)>
 
typedef std::shared_ptr< rs2_log_callbacklibrealsense::log_callback_ptr
 
typedef std::tuple< uint32_t, int, size_tlibrealsense::native_pixel_format_tuple
 
typedef void(* librealsense::notifications_callback_function_ptr) (rs2_notification *notification, void *user)
 
typedef std::shared_ptr< rs2_notifications_callbacklibrealsense::notifications_callback_ptr
 
typedef std::tuple< rs2_stream, int, rs2_formatlibrealsense::output_tuple
 
typedef std::tuple< platform::stream_profile_tuple, native_pixel_format_tuple, std::vector< output_tuple > > librealsense::request_mapping_tuple
 
using librealsense::resolution_func = std::function< resolution(resolution res)>
 
typedef void(* librealsense::software_device_destruction_callback_function_ptr) (void *user)
 
typedef std::shared_ptr< rs2_software_device_destruction_callbacklibrealsense::software_device_destruction_callback_ptr
 
typedef std::shared_ptr< rs2_update_progress_callbacklibrealsense::update_progress_callback_ptr
 

Enumerations

enum  res_type { low_resolution, medium_resolution, high_resolution }
 

Functions

template<typename T >
constexpr size_t librealsense::arr_size (T const &)
 
template<typename T , size_t sz>
constexpr size_t librealsense::arr_size (T(&arr)[sz])
 
template<typename T , size_t sz>
constexpr size_t librealsense::arr_size_bytes (T(&arr)[sz])
 
template<typename T >
std::string librealsense::array2str (T &data)
 
uint32_t librealsense::calc_crc32 (const uint8_t *buf, size_t bufsize)
 Calculate CRC code for arbitrary characters buffer. More...
 
float3x3 librealsense::calc_rotation_from_rodrigues_angles (const std::vector< double > rot)
 
bool librealsense::check_not_all_zeros (std::vector< byte > data)
 
template<typename T >
librealsense::clamp_val (T val, const T &min, const T &max)
 
template<class T >
bool contains (const T &first, const T &second)
 
void librealsense::copy (void *dst, void const *src, size_t size)
 
template<const bool force_narrowing = false, typename T , typename S , size_t tgt_m, size_t tgt_n, size_t src_m, size_t src_n>
size_t librealsense::copy_2darray (T(&dst)[tgt_m][tgt_n], const S(&src)[src_m][src_n])
 
template<const bool force_narrowing = false, typename T , typename S , size_t size_tgt, size_t size_src>
size_t librealsense::copy_array (T(&dst)[size_tgt], const S(&src)[size_src])
 
std::string librealsense::datetime_string ()
 
template<typename T >
deg2rad (T val)
 
void librealsense::enable_rolling_log_file (unsigned max_size)
 
bool librealsense::file_exists (const char *filename)
 
rs2_extrinsics librealsense::from_pose (pose a)
 
rs2_extrinsics librealsense::from_raw_extrinsics (rs2_extrinsics extr)
 
res_type get_res_type (uint32_t width, uint32_t height)
 
template<class T >
std::string librealsense::hexify (const T &val)
 
rs2_extrinsics librealsense::identity_matrix ()
 
pose librealsense::inverse (const pose &a)
 
rs2_extrinsics librealsense::inverse (const rs2_extrinsics &a)
 
void librealsense::log_to_callback (rs2_log_severity min_severity, log_callback_ptr callback)
 
void librealsense::log_to_console (rs2_log_severity min_severity)
 
void librealsense::log_to_file (rs2_log_severity min_severity, const char *file_path)
 
std::string librealsense::make_less_screamy (const char *str)
 
template<class T , class R , class W >
std::shared_ptr< struct_interface< T, R, W > > librealsense::make_struct_interface (R r, W w)
 
float3 librealsense::operator* (const float3 &a, float b)
 
float3 librealsense::operator* (const float3x3 &a, const float3 &b)
 
float3x3 librealsense::operator* (const float3x3 &a, const float3x3 &b)
 
float3 librealsense::operator* (const pose &a, const float3 &b)
 
pose librealsense::operator* (const pose &a, const pose &b)
 
float3 librealsense::operator+ (const float3 &a, const float3 &b)
 
float4 librealsense::operator+ (const float4 &a, const float4 &b)
 
float3 librealsense::operator- (const float3 &a, const float3 &b)
 
float4 librealsense::operator- (const float4 &a, const float4 &b)
 
bool librealsense::operator< (const stream_profile &lhs, const stream_profile &rhs)
 
std::ostream & librealsense::operator<< (std::ostream &stream, const float3 &elem)
 
std::ostream & librealsense::operator<< (std::ostream &stream, const float4 &elem)
 
std::ostream & librealsense::operator<< (std::ostream &stream, const float3x3 &elem)
 
std::ostream & librealsense::operator<< (std::ostream &stream, const pose &elem)
 
std::ostream & operator<< (std::ostream &out, rs2_extrinsics const &e)
 
std::ostream & operator<< (std::ostream &out, rs2_intrinsics const &i)
 
std::ostream & operator<< (std::ostream &s, rs2_dsm_params const &self)
 
bool librealsense::operator== (const float3 &a, const float3 &b)
 
bool librealsense::operator== (const float4 &a, const float4 &b)
 
bool librealsense::operator== (const float3x3 &a, const float3x3 &b)
 
bool librealsense::operator== (const pose &a, const pose &b)
 
bool librealsense::operator== (const stream_profile &a, const stream_profile &b)
 
bool librealsense::operator== (const rs2_intrinsics &a, const rs2_intrinsics &b)
 
bool librealsense::operator== (const uvc_device_info &a, const uvc_device_info &b)
 
bool librealsense::operator== (const usb_device_info &a, const usb_device_info &b)
 
bool librealsense::operator== (const hid_device_info &a, const hid_device_info &b)
 
bool operator== (const rs2_extrinsics &a, const rs2_extrinsics &b)
 
uint32_t librealsense::pack (uint8_t c0, uint8_t c1, uint8_t c2, uint8_t c3)
 
rs2_intrinsics librealsense::pad_crop_intrinsics (const rs2_intrinsics &i, int pad_crop)
 
template<typename T >
rad2deg (T val)
 
void librealsense::reset_logger ()
 
template<typename T >
uint32_t rs_fourcc (const T a, const T b, const T c, const T d)
 
rs2_intrinsics librealsense::scale_intrinsics (const rs2_intrinsics &i, int width, int height)
 
template<class T >
std::vector< std::shared_ptr< T > > subtract_sets (const std::vector< std::shared_ptr< T >> &first, const std::vector< std::shared_ptr< T >> &second)
 
pose librealsense::to_pose (const rs2_extrinsics &a)
 
rs2_extrinsics librealsense::to_raw_extrinsics (rs2_extrinsics extr)
 
float3x3 librealsense::transpose (const float3x3 &a)
 
template<typename T >
bool librealsense::val_in_range (const T &val, const std::initializer_list< T > &list)
 

Variables

static const double d2r = pi / 180
 
static const double pi = std::acos(-1)
 
static const double r2d = 180 / pi
 
const int RS2_USER_QUEUE_SIZE = 128
 
static const double librealsense::TIMESTAMP_USEC_TO_MSEC = 0.001
 

Macro Definition Documentation

#define _USE_MATH_DEFINES

Definition at line 26 of file src/types.h.

#define LIBREALSENSE_TYPES_H

Definition at line 10 of file src/types.h.

#define LOG_DEBUG (   ...)    do { ; } while(false)

Definition at line 239 of file src/types.h.

#define LOG_ERROR (   ...)    do { ; } while(false)

Definition at line 242 of file src/types.h.

#define LOG_FATAL (   ...)    do { ; } while(false)

Definition at line 243 of file src/types.h.

#define LOG_INFO (   ...)    do { ; } while(false)

Definition at line 240 of file src/types.h.

#define LOG_WARNING (   ...)    do { ; } while(false)

Definition at line 241 of file src/types.h.

#define LRS_EXTENSION_API

Definition at line 20 of file src/types.h.

#define PRIVATE_TESTABLE   private

Definition at line 264 of file src/types.h.

#define RS2_ENUM_HELPERS (   TYPE,
  PREFIX 
)    RS2_ENUM_HELPERS_CUSTOMIZED( TYPE, 0, RS2_##PREFIX##_COUNT - 1 )

Definition at line 514 of file src/types.h.

#define RS2_ENUM_HELPERS_CUSTOMIZED (   TYPE,
  FIRST,
  LAST 
)
Value:
LRS_EXTENSION_API const char * get_string( TYPE value ); \
inline bool is_valid( TYPE value ) { return value >= FIRST && value <= LAST; } \
inline std::ostream & operator<<( std::ostream & out, TYPE value ) \
{ \
if( is_valid( value ) ) \
return out << get_string( value ); \
else \
return out << (int)value; \
} \
inline bool try_parse( const std::string & str, TYPE & res ) \
{ \
for( int i = FIRST; i <= LAST; i++ ) \
{ \
auto v = static_cast< TYPE >( i ); \
if( str == get_string( v ) ) \
{ \
res = v; \
return true; \
} \
} \
return false; \
}
std::ostream & operator<<(std::ostream &out, rs2_extrinsics const &e)
Definition: src/types.h:1787
const char * get_string(rs2_rs400_visual_preset value)
GLfloat value
GLsizei const GLchar *const * string
#define LRS_EXTENSION_API
Definition: src/types.h:20
bool is_valid(const plane_3d &p)
Definition: rendering.h:243
int i
GLuint res
Definition: glext.h:8856
GLdouble v

Definition at line 518 of file src/types.h.

#define UNKNOWN_VALUE   "UNKNOWN"

Definition at line 74 of file src/types.h.

Typedef Documentation

typedef unsigned char byte

Definition at line 52 of file src/types.h.

Enumeration Type Documentation

enum res_type
Enumerator
low_resolution 
medium_resolution 
high_resolution 

Definition at line 1920 of file src/types.h.

Function Documentation

template<class T >
bool contains ( const T &  first,
const T &  second 
)

Definition at line 1899 of file src/types.h.

template<typename T >
T deg2rad ( val)

Definition at line 60 of file src/types.h.

res_type get_res_type ( uint32_t  width,
uint32_t  height 
)
inline

Definition at line 1926 of file src/types.h.

std::ostream& operator<< ( std::ostream &  out,
rs2_extrinsics const &  e 
)
inline

Definition at line 1787 of file src/types.h.

std::ostream& operator<< ( std::ostream &  out,
rs2_intrinsics const &  i 
)
inline

Definition at line 1796 of file src/types.h.

std::ostream& operator<< ( std::ostream &  s,
rs2_dsm_params const &  self 
)
inline

Definition at line 1808 of file src/types.h.

bool operator== ( const rs2_extrinsics a,
const rs2_extrinsics b 
)
inline

Definition at line 1939 of file src/types.h.

template<typename T >
T rad2deg ( val)

Definition at line 61 of file src/types.h.

template<typename T >
uint32_t rs_fourcc ( const T  a,
const T  b,
const T  c,
const T  d 
)

Definition at line 1846 of file src/types.h.

template<class T >
std::vector<std::shared_ptr<T> > subtract_sets ( const std::vector< std::shared_ptr< T >> &  first,
const std::vector< std::shared_ptr< T >> &  second 
)

Definition at line 1905 of file src/types.h.

Variable Documentation

const double d2r = pi / 180
static

Definition at line 58 of file src/types.h.

const double pi = std::acos(-1)
static

Definition at line 57 of file src/types.h.

const double r2d = 180 / pi
static

Definition at line 59 of file src/types.h.

const int RS2_USER_QUEUE_SIZE = 128

Definition at line 54 of file src/types.h.



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