Classes | Macros | Functions | Variables
python.hpp File Reference
#include <pybind11/pybind11.h>
#include <pybind11/operators.h>
#include <pybind11/stl.h>
#include <pybind11/chrono.h>
#include <pybind11/stl_bind.h>
#include <pybind11/functional.h>
#include "../include/librealsense2/h/rs_sensor.h"
Include dependency graph for python.hpp:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

class  BufData
 
struct  fmtstring< FMT >
 
struct  FmtToType< rs2_format >
 
struct  itemsize< FMT >
 

Macros

#define BIND_DOWNCAST(class, downcast)   "is_"#downcast, &rs2::class::is<rs2::downcast>).def("as_"#downcast, &rs2::class::as<rs2::downcast>
 
#define BIND_ENUM(module, rs2_enum_type, RS2_ENUM_COUNT, docstring)   BIND_ENUM_CUSTOM( module, rs2_enum_type, 0, RS2_ENUM_COUNT-1, docstring)
 
#define BIND_ENUM_CUSTOM(module, rs2_enum_type, FIRST, LAST, docstring)
 
#define BIND_RAW_2D_ARRAY_GETTER(T, member, valueT, NROWS, NCOLS)   [](const T& self) -> const std::array<std::array<valueT, NCOLS>, NROWS>& { return reinterpret_cast<const std::array<std::array<valueT, NCOLS>, NROWS>&>(self.member); }
 
#define BIND_RAW_2D_ARRAY_PROPERTY(T, member, valueT, NROWS, NCOLS)   #member, BIND_RAW_2D_ARRAY_GETTER(T, member, valueT, NROWS, NCOLS), BIND_RAW_2D_ARRAY_SETTER(T, member, valueT, NROWS, NCOLS)
 
#define BIND_RAW_2D_ARRAY_SETTER(T, member, valueT, NROWS, NCOLS)   [](T& self, const std::array<std::array<valueT, NCOLS>, NROWS>& src) { copy_raw_2d_array(self.member, src); }
 
#define BIND_RAW_ARRAY_GETTER(T, member, valueT, SIZE)   [](const T& self) -> const std::array<valueT, SIZE>& { return reinterpret_cast<const std::array<valueT, SIZE>&>(self.member); }
 
#define BIND_RAW_ARRAY_PROPERTY(T, member, valueT, SIZE)   #member, BIND_RAW_ARRAY_GETTER(T, member, valueT, SIZE), BIND_RAW_ARRAY_SETTER(T, member, valueT, SIZE)
 
#define BIND_RAW_ARRAY_SETTER(T, member, valueT, SIZE)   [](T& self, const std::array<valueT, SIZE>& src) { copy_raw_array(self.member, src); }
 
#define MAP_FMT_TO_TYPE(F, T)   template <> struct FmtToType<F> { using type = T; }
 
#define NAME   pyrealsense2
 
#define SNAME   "pyrealsense2"
 

Functions

template<typename T , size_t N>
std::string array_to_string (const T(&arr)[N])
 
template<typename T , size_t NROWS, size_t NCOLS>
void copy_raw_2d_array (T(&dst)[NROWS][NCOLS], const std::array< std::array< T, NCOLS >, NROWS > &src)
 
template<typename T , size_t SIZE>
void copy_raw_array (T(&dst)[SIZE], const std::array< T, SIZE > &src)
 
template<template< rs2_format > class F>
auto fmt_to_value (rs2_format fmt) -> typename std::result_of< decltype(&F< RS2_FORMAT_ANY >::func)()>::type
 
void init_advanced_mode (py::module &m)
 
void init_c_files (py::module &m)
 
void init_context (py::module &m)
 
void init_device (py::module &m)
 
void init_export (py::module &m)
 
void init_frame (py::module &m)
 
void init_internal (py::module &m)
 
void init_options (py::module &m)
 
void init_pipeline (py::module &m)
 
void init_processing (py::module &m)
 
void init_record_playback (py::module &m)
 
void init_sensor (py::module &m)
 
void init_serializable_device (py::module &m)
 
void init_types (py::module &m)
 
void init_util (py::module &m)
 
std::string make_pythonic_str (std::string str)
 
 MAP_FMT_TO_TYPE (RS2_FORMAT_Z16, uint16_t)
 
 MAP_FMT_TO_TYPE (RS2_FORMAT_XYZ32F, float)
 
 MAP_FMT_TO_TYPE (RS2_FORMAT_YUYV, uint8_t)
 
 MAP_FMT_TO_TYPE (RS2_FORMAT_RGB8, uint8_t)
 
 MAP_FMT_TO_TYPE (RS2_FORMAT_BGR8, uint8_t)
 
 MAP_FMT_TO_TYPE (RS2_FORMAT_RGBA8, uint8_t)
 
 MAP_FMT_TO_TYPE (RS2_FORMAT_BGRA8, uint8_t)
 
 MAP_FMT_TO_TYPE (RS2_FORMAT_Y8, uint8_t)
 
 MAP_FMT_TO_TYPE (RS2_FORMAT_Y16, uint16_t)
 
 MAP_FMT_TO_TYPE (RS2_FORMAT_RAW16, uint16_t)
 
 MAP_FMT_TO_TYPE (RS2_FORMAT_RAW8, uint8_t)
 
 MAP_FMT_TO_TYPE (RS2_FORMAT_UYVY, uint8_t)
 
 MAP_FMT_TO_TYPE (RS2_FORMAT_MOTION_XYZ32F, float)
 
 MAP_FMT_TO_TYPE (RS2_FORMAT_DISPARITY32, float)
 
 MAP_FMT_TO_TYPE (RS2_FORMAT_Y10BPACK, uint8_t)
 
 MAP_FMT_TO_TYPE (RS2_FORMAT_DISTANCE, float)
 
 MAP_FMT_TO_TYPE (RS2_FORMAT_Y8I, uint8_t)
 
 MAP_FMT_TO_TYPE (RS2_FORMAT_INVI, uint8_t)
 
 MAP_FMT_TO_TYPE (RS2_FORMAT_FG, uint16_t)
 
template<typename T , size_t N, size_t M>
std::string matrix_to_string (const T(&arr)[N][M])
 

Variables

const std::string rs2_prefix { "rs2_" }
 

Macro Definition Documentation

#define BIND_DOWNCAST (   class,
  downcast 
)    "is_"#downcast, &rs2::class::is<rs2::downcast>).def("as_"#downcast, &rs2::class::as<rs2::downcast>

Definition at line 33 of file python.hpp.

#define BIND_ENUM (   module,
  rs2_enum_type,
  RS2_ENUM_COUNT,
  docstring 
)    BIND_ENUM_CUSTOM( module, rs2_enum_type, 0, RS2_ENUM_COUNT-1, docstring)

Definition at line 38 of file python.hpp.

#define BIND_ENUM_CUSTOM (   module,
  rs2_enum_type,
  FIRST,
  LAST,
  docstring 
)
Value:
static std::string rs2_enum_type##pyclass_name = std::string(#rs2_enum_type).substr(rs2_prefix.length()); \
/* Above 'static' is required in order to keep the string alive since py::class_ does not copy it */ \
py::enum_<rs2_enum_type> py_##rs2_enum_type(module, rs2_enum_type##pyclass_name.c_str(), docstring); \
/* std::cout << std::endl << "## " << rs2_enum_type##pyclass_name << ":" << std::endl; */ \
for (int i = FIRST; i <= LAST; i++) \
{ \
rs2_enum_type v = static_cast<rs2_enum_type>(i); \
const char* enum_name = rs2_enum_type##_to_string(v); \
auto python_name = make_pythonic_str(enum_name); \
py_##rs2_enum_type.value(python_name.c_str(), v); \
/* std::cout << " - " << python_name << std::endl; */ \
}
GLsizei const GLchar *const * string
std::string make_pythonic_str(std::string str)
Definition: c_files.cpp:9
const std::string rs2_prefix
Definition: python.hpp:36
int i
GLdouble v

Definition at line 39 of file python.hpp.

#define BIND_RAW_2D_ARRAY_GETTER (   T,
  member,
  valueT,
  NROWS,
  NCOLS 
)    [](const T& self) -> const std::array<std::array<valueT, NCOLS>, NROWS>& { return reinterpret_cast<const std::array<std::array<valueT, NCOLS>, NROWS>&>(self.member); }

Definition at line 114 of file python.hpp.

#define BIND_RAW_2D_ARRAY_PROPERTY (   T,
  member,
  valueT,
  NROWS,
  NCOLS 
)    #member, BIND_RAW_2D_ARRAY_GETTER(T, member, valueT, NROWS, NCOLS), BIND_RAW_2D_ARRAY_SETTER(T, member, valueT, NROWS, NCOLS)

Definition at line 118 of file python.hpp.

#define BIND_RAW_2D_ARRAY_SETTER (   T,
  member,
  valueT,
  NROWS,
  NCOLS 
)    [](T& self, const std::array<std::array<valueT, NCOLS>, NROWS>& src) { copy_raw_2d_array(self.member, src); }

Definition at line 115 of file python.hpp.

#define BIND_RAW_ARRAY_GETTER (   T,
  member,
  valueT,
  SIZE 
)    [](const T& self) -> const std::array<valueT, SIZE>& { return reinterpret_cast<const std::array<valueT, SIZE>&>(self.member); }

Definition at line 111 of file python.hpp.

#define BIND_RAW_ARRAY_PROPERTY (   T,
  member,
  valueT,
  SIZE 
)    #member, BIND_RAW_ARRAY_GETTER(T, member, valueT, SIZE), BIND_RAW_ARRAY_SETTER(T, member, valueT, SIZE)

Definition at line 117 of file python.hpp.

#define BIND_RAW_ARRAY_SETTER (   T,
  member,
  valueT,
  SIZE 
)    [](T& self, const std::array<valueT, SIZE>& src) { copy_raw_array(self.member, src); }

Definition at line 112 of file python.hpp.

#define MAP_FMT_TO_TYPE (   F,
 
)    template <> struct FmtToType<F> { using type = T; }

Definition at line 123 of file python.hpp.

#define NAME   pyrealsense2

Definition at line 24 of file python.hpp.

#define SNAME   "pyrealsense2"

Definition at line 25 of file python.hpp.

Function Documentation

template<typename T , size_t N>
std::string array_to_string ( const T(&)  arr[N])

Definition at line 75 of file python.hpp.

template<typename T , size_t NROWS, size_t NCOLS>
void copy_raw_2d_array ( T(&)  dst[NROWS][NCOLS],
const std::array< std::array< T, NCOLS >, NROWS > &  src 
)

Definition at line 64 of file python.hpp.

template<typename T , size_t SIZE>
void copy_raw_array ( T(&)  dst[SIZE],
const std::array< T, SIZE > &  src 
)

Definition at line 55 of file python.hpp.

template<template< rs2_format > class F>
auto fmt_to_value ( rs2_format  fmt) -> typename std::result_of<decltype(&F<RS2_FORMAT_ANY>::func)()>::type

Definition at line 160 of file python.hpp.

void init_advanced_mode ( py::module &  m)

RS400 Advanced Mode commands

Definition at line 8 of file pyrs_advanced_mode.cpp.

void init_c_files ( py::module &  m)

Binding of rs2_* enums

rs_types.h

end rs_types.h

rs_sensor.h

end rs_sensor.h

Definition at line 21 of file c_files.cpp.

void init_context ( py::module &  m)

end rs_context.hpp

Definition at line 7 of file pyrs_context.cpp.

void init_device ( py::module &  m)

rs_device.hpp

end rs_device.hpp

Definition at line 9 of file pyrs_device.cpp.

void init_export ( py::module &  m)

end rs_export.hpp

Definition at line 7 of file pyrs_export.cpp.

void init_frame ( py::module &  m)

end rs_frame.hpp

Definition at line 7 of file pyrs_frame.cpp.

void init_internal ( py::module &  m)

rs_internal.h

end rs_internal.h

rs_internal.hpp

end rs_internal.hpp

Definition at line 8 of file pyrs_internal.cpp.

void init_options ( py::module &  m)

rs_options.hpp

end rs_options.hpp

Definition at line 7 of file pyrs_options.cpp.

void init_pipeline ( py::module &  m)

rs_pipeline.hpp

end rs_pipeline.hpp

Definition at line 7 of file pyrs_pipeline.cpp.

void init_processing ( py::module &  m)

rs_processing.hpp

end rs_processing.hpp

Definition at line 7 of file pyrs_processing.cpp.

void init_record_playback ( py::module &  m)
void init_sensor ( py::module &  m)

rs_sensor.hpp

end rs_sensor.hpp

Definition at line 9 of file pyrs_sensor.cpp.

void init_serializable_device ( py::module &  m)

Definition at line 258 of file pyrs_advanced_mode.cpp.

void init_types ( py::module &  m)

rs2_types.hpp

end rs_types.hpp

Definition at line 7 of file pyrs_types.cpp.

void init_util ( py::module &  m)

rsutil.h

end rsutil.h

Definition at line 7 of file pyrsutil.cpp.

std::string make_pythonic_str ( std::string  str)

Definition at line 9 of file c_files.cpp.

MAP_FMT_TO_TYPE ( RS2_FORMAT_Z16  ,
uint16_t   
)
MAP_FMT_TO_TYPE ( RS2_FORMAT_XYZ32F  ,
float   
)
MAP_FMT_TO_TYPE ( RS2_FORMAT_YUYV  ,
uint8_t   
)
MAP_FMT_TO_TYPE ( RS2_FORMAT_RGB8  ,
uint8_t   
)
MAP_FMT_TO_TYPE ( RS2_FORMAT_BGR8  ,
uint8_t   
)
MAP_FMT_TO_TYPE ( RS2_FORMAT_RGBA8  ,
uint8_t   
)
MAP_FMT_TO_TYPE ( RS2_FORMAT_BGRA8  ,
uint8_t   
)
MAP_FMT_TO_TYPE ( RS2_FORMAT_Y8  ,
uint8_t   
)
MAP_FMT_TO_TYPE ( RS2_FORMAT_Y16  ,
uint16_t   
)
MAP_FMT_TO_TYPE ( RS2_FORMAT_RAW16  ,
uint16_t   
)
MAP_FMT_TO_TYPE ( RS2_FORMAT_RAW8  ,
uint8_t   
)
MAP_FMT_TO_TYPE ( RS2_FORMAT_UYVY  ,
uint8_t   
)
MAP_FMT_TO_TYPE ( RS2_FORMAT_MOTION_XYZ32F  ,
float   
)
MAP_FMT_TO_TYPE ( RS2_FORMAT_DISPARITY32  ,
float   
)
MAP_FMT_TO_TYPE ( RS2_FORMAT_Y10BPACK  ,
uint8_t   
)
MAP_FMT_TO_TYPE ( RS2_FORMAT_DISTANCE  ,
float   
)
MAP_FMT_TO_TYPE ( RS2_FORMAT_Y8I  ,
uint8_t   
)
MAP_FMT_TO_TYPE ( RS2_FORMAT_INVI  ,
uint8_t   
)
MAP_FMT_TO_TYPE ( RS2_FORMAT_FG  ,
uint16_t   
)
template<typename T , size_t N, size_t M>
std::string matrix_to_string ( const T(&)  arr[N][M])

Definition at line 90 of file python.hpp.

Variable Documentation

const std::string rs2_prefix { "rs2_" }

Definition at line 36 of file python.hpp.



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