pybackend.cpp
Go to the documentation of this file.
1 /* License: Apache 2.0. See LICENSE file in root directory.
2 Copyright(c) 2017 Intel Corporation. All Rights Reserved. */
3 
4 #include <pybind11/pybind11.h>
5 
6 // convenience functions
7 #include <pybind11/operators.h>
8 
9 // STL conversions
10 #include <pybind11/stl.h>
11 #include <pybind11/stl_bind.h>
12 
13 
14 // makes std::function conversions work
15 #include <pybind11/functional.h>
16 
17 #include "core/options.h" // Workaround for the missing DLL_EXPORT template
18 #include "core/info.h" // Workaround for the missing DLL_EXPORT template
19 #include "../src/backend.h"
20 #include "pybackend_extras.h"
21 #include "../../third-party/stb_image_write.h"
22 
23 #include <sstream>
24 #include <vector>
25 
26 #define NAME pybackend2
27 #define SNAME "pybackend2"
28 
29 namespace py = pybind11;
30 using namespace pybind11::literals;
31 
32 using namespace librealsense;
33 using namespace pybackend2;
34 
35 
36 // Prevents expensive copies of pixel buffers into python
37 PYBIND11_MAKE_OPAQUE(std::vector<uint8_t>)
38 
40 
41 
42  py::enum_<platform::usb_spec>(m, "USB_TYPE")
44  .value("USB1_1", platform::usb_spec::usb1_1_type)
45  .value("USB2", platform::usb_spec::usb2_type)
46  .value("USB2_1", platform::usb_spec::usb2_1_type)
47  .value("USB3", platform::usb_spec::usb3_type)
48  .value("USB3_1", platform::usb_spec::usb3_1_type)
49  .value("USB3_2", platform::usb_spec::usb3_2_type);
50 
51  m.doc() = "Wrapper for the backend of librealsense";
52 
53  py::class_<platform::control_range> control_range(m, "control_range");
54  control_range.def(py::init<>())
55  .def(py::init<int32_t, int32_t, int32_t, int32_t>(), "in_min"_a, "in_max"_a, "in_step"_a, "in_def"_a)
56  .def_readwrite("min", &platform::control_range::min)
57  .def_readwrite("max", &platform::control_range::max)
58  .def_readwrite("def", &platform::control_range::def)
59  .def_readwrite("step", &platform::control_range::step);
60 
61  py::class_<platform::time_service> time_service(m, "time_service");
62  time_service.def("get_time", &platform::time_service::get_time);
63 
64  py::class_<platform::os_time_service, platform::time_service> os_time_service(m, "os_time_service");
65 
66 #define BIND_RAW_RO_ARRAY(class, name, type, size) #name, [](const class &c) -> const std::array<type, size>& { return reinterpret_cast<const std::array<type, size>&>(c.name); }
67 #define BIND_RAW_RW_ARRAY(class, name, type, size) BIND_RAW_RO_ARRAY(class, name, type, size), [](class &c, const std::array<type, size> &arr) { for (int i=0; i<size; ++i) c.name[i] = arr[i]; }
68 
69  py::class_<platform::guid> guid(m, "guid");
70  guid.def_readwrite("data1", &platform::guid::data1)
71  .def_readwrite("data2", &platform::guid::data2)
72  .def_readwrite("data3", &platform::guid::data3)
73  .def_property(BIND_RAW_RW_ARRAY(platform::guid, data4, uint8_t, 8))
74  .def("__init__", [](platform::guid &g, uint32_t d1, uint32_t d2, uint32_t d3, std::array<uint8_t, 8> d4)
75  {
76  new (&g) platform::guid();
77  g.data1 = d1;
78  g.data2 = d2;
79  g.data3 = d3;
80  for (int i=0; i<8; ++i) g.data4[i] = d4[i];
81  }, "data1"_a, "data2"_a, "data3"_a, "data4"_a)
82  .def("__init__", [](platform::guid &g, const std::string &str)
83  {
84  new (&g) platform::guid(stoguid(str));
85  });
86 
87  py::class_<platform::extension_unit> extension_unit(m, "extension_unit");
88  extension_unit.def(py::init<>())
89  .def("__init__", [](platform::extension_unit & xu, int s, uint8_t u, int n, platform::guid g)
90  {
91  new (&xu) platform::extension_unit { s, u, n, g };
92  }, "subdevice"_a, "unit"_a, "node"_a, "guid"_a)
93  .def_readwrite("subdevice", &platform::extension_unit::subdevice)
94  .def_readwrite("unit", &platform::extension_unit::unit)
95  .def_readwrite("node", &platform::extension_unit::node)
96  .def_readwrite("id", &platform::extension_unit::id);
97 
98  py::class_<platform::command_transfer, std::shared_ptr<platform::command_transfer>> command_transfer(m, "command_transfer");
99  command_transfer.def("send_receive", &platform::command_transfer::send_receive, "data"_a, "timeout_ms"_a=5000, "require_response"_a=true);
100 
101  py::enum_<rs2_option> option(m, "option");
102  option.value("backlight_compensation", RS2_OPTION_BACKLIGHT_COMPENSATION)
103  .value("brightness", RS2_OPTION_BRIGHTNESS)
104  .value("contrast", RS2_OPTION_CONTRAST)
105  .value("exposure", RS2_OPTION_EXPOSURE)
106  .value("gain", RS2_OPTION_GAIN)
107  .value("gamma", RS2_OPTION_GAMMA)
108  .value("hue", RS2_OPTION_HUE)
109  .value("saturation", RS2_OPTION_SATURATION)
110  .value("sharpness", RS2_OPTION_SHARPNESS)
111  .value("white_balance", RS2_OPTION_WHITE_BALANCE)
112  .value("enable_auto_exposure", RS2_OPTION_ENABLE_AUTO_EXPOSURE)
113  .value("enable_auto_white_balance", RS2_OPTION_ENABLE_AUTO_WHITE_BALANCE)
114  .value("visual_preset", RS2_OPTION_VISUAL_PRESET)
115  .value("laser_power", RS2_OPTION_LASER_POWER)
116  .value("accuracy", RS2_OPTION_ACCURACY)
117  .value("motion_range", RS2_OPTION_MOTION_RANGE)
118  .value("filter_option", RS2_OPTION_FILTER_OPTION)
119  .value("confidence_threshold", RS2_OPTION_CONFIDENCE_THRESHOLD)
120  .value("emitter_enabled", RS2_OPTION_EMITTER_ENABLED)
121  .value("frames_queue_size", RS2_OPTION_FRAMES_QUEUE_SIZE)
122  .value("total_frame_drops", RS2_OPTION_TOTAL_FRAME_DROPS)
123  .value("auto_exposure_mode", RS2_OPTION_AUTO_EXPOSURE_MODE)
124  .value("power_line_frequency", RS2_OPTION_POWER_LINE_FREQUENCY)
125  .value("asic_temperature", RS2_OPTION_ASIC_TEMPERATURE)
126  .value("error_polling_enabled", RS2_OPTION_ERROR_POLLING_ENABLED)
127  .value("projector_temperature", RS2_OPTION_PROJECTOR_TEMPERATURE)
128  .value("output_trigger_enabled", RS2_OPTION_OUTPUT_TRIGGER_ENABLED)
129  .value("motion_module_temperature", RS2_OPTION_MOTION_MODULE_TEMPERATURE)
130  .value("depth_units", RS2_OPTION_DEPTH_UNITS)
131  .value("enable_motion_correction", RS2_OPTION_ENABLE_MOTION_CORRECTION)
132  .value("auto_exposure_priority", RS2_OPTION_AUTO_EXPOSURE_PRIORITY)
133  .value("color_scheme", RS2_OPTION_COLOR_SCHEME)
134  .value("histogram_equalization_enabled", RS2_OPTION_HISTOGRAM_EQUALIZATION_ENABLED)
135  .value("min_distance", RS2_OPTION_MIN_DISTANCE)
136  .value("max_distance", RS2_OPTION_MAX_DISTANCE)
137  .value("texture_source", RS2_OPTION_TEXTURE_SOURCE)
138  .value("filter_magnitude", RS2_OPTION_FILTER_MAGNITUDE)
139  .value("filter_smooth_alpha", RS2_OPTION_FILTER_SMOOTH_ALPHA)
140  .value("filter_smooth_delta", RS2_OPTION_FILTER_SMOOTH_DELTA)
141  .value("filter_holes_fill", RS2_OPTION_HOLES_FILL)
142  .value("stereo_baseline", RS2_OPTION_STEREO_BASELINE)
143  .value("auto_exposure_converge_step", RS2_OPTION_AUTO_EXPOSURE_CONVERGE_STEP)
144  .value("inter_cam_sync_mode", RS2_OPTION_INTER_CAM_SYNC_MODE)
145  .value("stream_filter", RS2_OPTION_STREAM_FILTER)
146  .value("stream_format_filter", RS2_OPTION_STREAM_FORMAT_FILTER)
147  .value("stream_index_filter", RS2_OPTION_STREAM_INDEX_FILTER)
148  .value("emitter_on_off", RS2_OPTION_EMITTER_ON_OFF)
149  .value("zero_order_point_x", RS2_OPTION_ZERO_ORDER_POINT_X) // Deprecated
150  .value("zero_order_point_y", RS2_OPTION_ZERO_ORDER_POINT_Y) // Deprecated
151  .value("lld_temperature", RS2_OPTION_LLD_TEMPERATURE)
152  .value("mc_temperature", RS2_OPTION_MC_TEMPERATURE)
153  .value("ma_temperature", RS2_OPTION_MA_TEMPERATURE)
154  .value("hardware_preset", RS2_OPTION_HARDWARE_PRESET)
155  .value("global_time_enabled", RS2_OPTION_GLOBAL_TIME_ENABLED)
156  .value("apd_temperature", RS2_OPTION_APD_TEMPERATURE)
157  .value("enable_mapping", RS2_OPTION_ENABLE_MAPPING)
158  .value("enable_relocalization", RS2_OPTION_ENABLE_RELOCALIZATION)
159  .value("enable_pose_jumping", RS2_OPTION_ENABLE_POSE_JUMPING)
160  .value("enable_dynamic_calibration", RS2_OPTION_ENABLE_DYNAMIC_CALIBRATION)
161  .value("enable_depth_offset", RS2_OPTION_DEPTH_OFFSET)
162  .value("enable_led_power", RS2_OPTION_LED_POWER)
163  .value("zero_order_enabled", RS2_OPTION_ZERO_ORDER_ENABLED) // Deprecated
164  .value("enable_map_preservation", RS2_OPTION_ENABLE_MAP_PRESERVATION)
165  .value("enable_freefall_detection", RS2_OPTION_FREEFALL_DETECTION_ENABLED)
166  .value("exposure_time_receiver_APD", RS2_OPTION_AVALANCHE_PHOTO_DIODE)
167  .value("post_processing_sharpening_level", RS2_OPTION_POST_PROCESSING_SHARPENING)
168  .value("pre_processing_sharpening_level", RS2_OPTION_PRE_PROCESSING_SHARPENING)
169  .value("edge_background_noise_level", RS2_OPTION_NOISE_FILTERING)
170  .value("activate_pixel_invalidation", RS2_OPTION_INVALIDATION_BYPASS)
171  .value("ambient_light_environment_level", RS2_OPTION_AMBIENT_LIGHT)
172  .value("digital_gain", RS2_OPTION_DIGITAL_GAIN)
173  .value("sensor_resolution_mode", RS2_OPTION_SENSOR_MODE)
174  .value("emitter_always_on", RS2_OPTION_EMITTER_ALWAYS_ON)
175  .value("thermal_compensation", RS2_OPTION_THERMAL_COMPENSATION)
176  .value("trigger_camera_accuracy_health", RS2_OPTION_TRIGGER_CAMERA_ACCURACY_HEALTH)
177  .value("reset_camera_accuracy_health", RS2_OPTION_RESET_CAMERA_ACCURACY_HEALTH)
178  .value("host_performance", RS2_OPTION_HOST_PERFORMANCE)
179  .value("hdr_enabled", RS2_OPTION_HDR_ENABLED)
180  .value("sequence_name", RS2_OPTION_SEQUENCE_NAME)
181  .value("sequence_size", RS2_OPTION_SEQUENCE_SIZE)
182  .value("sequence_id", RS2_OPTION_SEQUENCE_ID)
183  .value("humidity_temperature", RS2_OPTION_HUMIDITY_TEMPERATURE)
184  .value("enable_max_usable_range", RS2_OPTION_ENABLE_MAX_USABLE_RANGE)
185  .value("alternate_ir", RS2_OPTION_ALTERNATE_IR)
186  .value("noise_estimation", RS2_OPTION_NOISE_ESTIMATION)
187  .value("enable_ir_reflectivity", RS2_OPTION_ENABLE_IR_REFLECTIVITY)
188  .value("auto_exposure_limit", RS2_OPTION_AUTO_EXPOSURE_LIMIT)
189  .value("auto_gain_limit", RS2_OPTION_AUTO_GAIN_LIMIT)
190  .value("count", RS2_OPTION_COUNT);
191 
192  py::enum_<platform::power_state> power_state(m, "power_state");
193  power_state.value("D0", platform::power_state::D0)
194  .value("D3", platform::power_state::D3);
195  power_state.export_values();
196 
197  py::class_<platform::stream_profile> stream_profile(m, "stream_profile");
198  stream_profile.def_readwrite("width", &platform::stream_profile::width)
199  .def_readwrite("height", &platform::stream_profile::height)
200  .def_readwrite("fps", &platform::stream_profile::fps)
201  .def_readwrite("format", &platform::stream_profile::format)
202 // .def("stream_profile_tuple", &platform::stream_profile::stream_profile_tuple) // converstion operator to std::tuple
203  .def(py::self == py::self).def("__repr__", [](const platform::stream_profile &p) {
204  std::stringstream ss;
205  ss << "<" SNAME ".stream_profile: "
206  << p.width
207  << "x" << p.height << " @ " << p.fps << "fps "
208  << std::hex << p.format << ">";
209  return ss.str();
210  });;
211 
212  // Bind std::vector<uint8_t> to act like a pythonic list
213  py::bind_vector<std::vector<uint8_t>>(m, "VectorByte");
214 
215  py::class_<platform::frame_object> frame_object(m, "frame_object");
216  frame_object.def_readwrite("frame_size", &platform::frame_object::frame_size)
217  .def_readwrite("metadata_size", &platform::frame_object::metadata_size)
218  .def_property_readonly("pixels", [](const platform::frame_object &f) { return std::vector<uint8_t>(static_cast<const uint8_t*>(f.pixels), static_cast<const uint8_t*>(f.pixels)+f.frame_size);})
219  .def_property_readonly("metadata", [](const platform::frame_object &f) { return std::vector<uint8_t>(static_cast<const uint8_t*>(f.metadata), static_cast<const uint8_t*>(f.metadata)+f.metadata_size);})
220  .def("save_png", [](const platform::frame_object &f, std::string fn, int w, int h, int bpp, int s)
221  {
222  stbi_write_png(fn.c_str(), w, h, bpp, f.pixels, s);
223  }, "filename"_a, "width"_a, "height"_a, "bytes_per_pixel"_a, "stride"_a)
224  .def("save_png", [](const platform::frame_object &f, std::string fn, int w, int h, int bpp)
225  {
226  stbi_write_png(fn.c_str(), w, h, bpp, f.pixels, w*bpp);
227  }, "filename"_a, "width"_a, "height"_a, "bytes_per_pixel"_a);
228 
229  py::class_<platform::uvc_device_info> uvc_device_info(m, "uvc_device_info");
230  uvc_device_info.def_readwrite("id", &platform::uvc_device_info::id, "To distinguish between different pins of the same device.")
231  .def_readwrite("vid", &platform::uvc_device_info::vid)
232  .def_readwrite("pid", &platform::uvc_device_info::pid)
233  .def_readwrite("mi", &platform::uvc_device_info::mi)
234  .def_readwrite("unique_id", &platform::uvc_device_info::unique_id)
235  .def_readwrite("device_path", &platform::uvc_device_info::device_path)
236  .def(py::self == py::self);
237 
238  py::class_<platform::usb_device_info> usb_device_info(m, "usb_device_info");
239  usb_device_info.def_readwrite("id", &platform::usb_device_info::id)
240  .def_readwrite("vid", &platform::usb_device_info::vid)
241  .def_readwrite("pid", &platform::usb_device_info::pid)
242  .def_readwrite("mi", &platform::usb_device_info::mi)
243  .def_readwrite("unique_id", &platform::usb_device_info::unique_id);
244 
245  py::class_<platform::hid_device_info> hid_device_info(m, "hid_device_info");
246  hid_device_info.def_readwrite("id", &platform::hid_device_info::id)
247  .def_readwrite("vid", &platform::hid_device_info::vid)
248  .def_readwrite("pid", &platform::hid_device_info::pid)
249  .def_readwrite("unique_id", &platform::hid_device_info::unique_id)
250  .def_readwrite("device_path", &platform::hid_device_info::device_path);
251 
252  py::class_<platform::hid_sensor> hid_sensor(m, "hid_sensor");
253  hid_sensor.def_readwrite("name", &platform::hid_sensor::name);
254 
255  py::class_<platform::hid_sensor_input> hid_sensor_input(m, "hid_sensor_input");
256  hid_sensor_input.def_readwrite("index", &platform::hid_sensor_input::index)
257  .def_readwrite("name", &platform::hid_sensor_input::name);
258 
259  py::class_<platform::callback_data> callback_data(m, "callback_data");
260  callback_data.def_readwrite("sensor", &platform::callback_data::sensor)
261  .def_readwrite("sensor_input", &platform::callback_data::sensor_input)
262  .def_readwrite("value", &platform::callback_data::value);
263 
264  py::class_<platform::sensor_data> sensor_data(m, "sensor_data");
265  sensor_data.def_readwrite("sensor", &platform::sensor_data::sensor)
266  .def_readwrite("fo", &platform::sensor_data::fo);
267 
268  py::class_<platform::hid_profile> hid_profile(m, "hid_profile");
269  hid_profile.def(py::init<>())
270  .def_readwrite("sensor_name", &platform::hid_profile::sensor_name)
271  .def_readwrite("frequency", &platform::hid_profile::frequency);
272 
273  py::enum_<platform::custom_sensor_report_field> custom_sensor_report_field(m, "custom_sensor_report_field");
274  custom_sensor_report_field.value("minimum", platform::custom_sensor_report_field::minimum)
281  custom_sensor_report_field.export_values();
282 
283  py::class_<platform::hid_sensor_data> hid_sensor_data(m, "hid_sensor_data");
284  hid_sensor_data.def_readwrite("x", &platform::hid_sensor_data::x)
285  .def_property(BIND_RAW_RW_ARRAY(platform::hid_sensor_data, reserved1, char, 2))
286  .def_readwrite("y", &platform::hid_sensor_data::y)
287  .def_property(BIND_RAW_RW_ARRAY(platform::hid_sensor_data, reserved2, char, 2))
288  .def_readwrite("z", &platform::hid_sensor_data::z)
289  .def_property(BIND_RAW_RW_ARRAY(platform::hid_sensor_data, reserved3, char, 2))
290  .def_readwrite("ts_low", &platform::hid_sensor_data::ts_low)
291  .def_readwrite("ts_high", &platform::hid_sensor_data::ts_high);
292 
293  py::class_<platform::hid_device, std::shared_ptr<platform::hid_device>> hid_device(m, "hid_device");
294 
295  hid_device.def("open", &platform::hid_device::open, "hid_profiles"_a)
296  .def("close", &platform::hid_device::close)
297  .def("stop_capture", &platform::hid_device::stop_capture, py::call_guard<py::gil_scoped_release>())
298  .def("start_capture", &platform::hid_device::start_capture, "callback"_a)
299  .def("get_sensors", &platform::hid_device::get_sensors)
300  .def("get_custom_report_data", &platform::hid_device::get_custom_report_data,
301  "custom_sensor_name"_a, "report_name"_a, "report_field"_a);
302 
303  py::class_<platform::multi_pins_hid_device, std::shared_ptr<platform::multi_pins_hid_device>, platform::hid_device> multi_pins_hid_device(m, "multi_pins_hid_device");
304 
305  multi_pins_hid_device.def(py::init<std::vector<std::shared_ptr<platform::hid_device>>&>())
306  .def("open", &platform::multi_pins_hid_device::open, "hid_profiles"_a)
307  .def("close", &platform::multi_pins_hid_device::close)
308  .def("stop_capture", &platform::multi_pins_hid_device::stop_capture, py::call_guard<py::gil_scoped_release>())
309  .def("start_capture", &platform::multi_pins_hid_device::start_capture, "callback"_a)
310  .def("get_sensors", &platform::multi_pins_hid_device::get_sensors)
311  .def("get_custom_report_data", &platform::multi_pins_hid_device::get_custom_report_data,
312  "custom_sensor_name"_a, "report_name"_a, "report_field"_a);
313 
314  py::class_<platform::uvc_device, std::shared_ptr<platform::uvc_device>> uvc_device(m, "uvc_device");
315 
316  py::class_<platform::retry_controls_work_around, std::shared_ptr<platform::retry_controls_work_around>, platform::uvc_device> retry_controls_work_around(m, "retry_controls_work_around");
317 
318  retry_controls_work_around.def(py::init<std::shared_ptr<platform::uvc_device>>())
319  .def("probe_and_commit",
321  std::function<void(platform::frame_object)> callback) {
322  dev.probe_and_commit(profile, [=](platform::stream_profile p,
323  platform::frame_object fo, std::function<void()> next)
324  {
325  callback(fo);
326  next();
327  }, 4);
328  }
329  , "profile"_a, "callback"_a)
330  .def("stream_on", [](platform::retry_controls_work_around& dev) {
331  dev.stream_on([](const notification& n)
332  {
333  });
334  })
335  .def("start_callbacks", &platform::retry_controls_work_around::start_callbacks)
336  .def("stop_callbacks", &platform::retry_controls_work_around::stop_callbacks)
337  .def("get_usb_specification", &platform::retry_controls_work_around::get_usb_specification)
338  .def("close", [](platform::retry_controls_work_around &dev, platform::stream_profile profile)
339  {
340  py::gil_scoped_release release;
341  dev.close(profile);
342  }, "profile"_a)
343  .def("set_power_state", &platform::retry_controls_work_around::set_power_state, "state"_a)
344  .def("get_power_state", &platform::retry_controls_work_around::get_power_state)
345  .def("init_xu", &platform::retry_controls_work_around::init_xu, "xu"_a)
346  .def("set_xu", [](platform::retry_controls_work_around &dev, const platform::extension_unit &xu, uint8_t ctrl, py::list l)
347  {
348  std::vector<uint8_t> data(l.size());
349  for (int i = 0; i < l.size(); ++i)
350  data[i] = l[i].cast<uint8_t>();
351  return dev.set_xu(xu, ctrl, data.data(), (int)data.size());
352  }, "xu"_a, "ctrl"_a, "data"_a)
353  .def("set_xu", [](platform::retry_controls_work_around &dev, const platform::extension_unit &xu, uint8_t ctrl, std::vector<uint8_t> &data)
354  {
355  return dev.set_xu(xu, ctrl, data.data(), (int)data.size());
356  }, "xu"_a, "ctrl"_a, "data"_a)
357  .def("get_xu", [](const platform::retry_controls_work_around &dev, const platform::extension_unit &xu, uint8_t ctrl, size_t len)
358  {
359  std::vector<uint8_t> data(len);
360  dev.get_xu(xu, ctrl, data.data(), (int)len);
361  py::list ret(len);
362  for (size_t i = 0; i < len; ++i)
363  ret[i] = data[i];
364  return ret;
365  }, "xu"_a, "ctrl"_a, "len"_a)
366  .def("get_xu_range", &platform::retry_controls_work_around::get_xu_range, "xu"_a, "ctrl"_a, "len"_a)
367  .def("get_pu", [](platform::retry_controls_work_around& dev, rs2_option opt) {
368  int val = 0;
369  dev.get_pu(opt, val);
370  return val;
371  }, "opt"_a)
372  .def("set_pu", &platform::retry_controls_work_around::set_pu, "opt"_a, "value"_a)
373  .def("get_pu_range", &platform::retry_controls_work_around::get_pu_range, "opt"_a)
374  .def("get_profiles", &platform::retry_controls_work_around::get_profiles)
377  .def("get_device_location", &platform::retry_controls_work_around::get_device_location);
378 
379  //py::class_<platform::usb_device, platform::command_transfer, std::shared_ptr<platform::usb_device>> usb_device(m, "usb_device");
380 
381  py::class_<platform::backend, std::shared_ptr<platform::backend>> backend(m, "backend");
382  backend.def("create_uvc_device", &platform::backend::create_uvc_device, "info"_a)
383  .def("query_uvc_devices", &platform::backend::query_uvc_devices)
384  .def("create_usb_device", &platform::backend::create_usb_device, "info"_a)
385  .def("query_usb_devices", &platform::backend::query_usb_devices)
386  .def("create_hid_device", &platform::backend::create_hid_device, "info"_a)
387  .def("query_hid_devices", &platform::backend::query_hid_devices)
388  .def("create_time_service", &platform::backend::create_time_service);
389 
390  py::class_<platform::multi_pins_uvc_device, std::shared_ptr<platform::multi_pins_uvc_device>, platform::uvc_device> multi_pins_uvc_device(m, "multi_pins_uvc_device");
391  multi_pins_uvc_device.def(py::init<std::vector<std::shared_ptr<platform::uvc_device>>&>())
392  .def("probe_and_commit",
394  std::function<void(platform::frame_object)> callback) {
395  dev.probe_and_commit(profile, [=](platform::stream_profile p,
396  platform::frame_object fo, std::function<void()> next)
397  {
398  callback(fo);
399  next();
400  }, 4);
401  }
402  , "profile"_a, "callback"_a)
403  .def("stream_on", [](platform::multi_pins_uvc_device& dev) {
404  dev.stream_on([](const notification& n)
405  {
406  });
407  })
408  .def("start_callbacks", &platform::multi_pins_uvc_device::start_callbacks)
409  .def("stop_callbacks", &platform::multi_pins_uvc_device::stop_callbacks)
410  .def("get_usb_specification", &platform::multi_pins_uvc_device::get_usb_specification)
411  .def("close", [](platform::multi_pins_uvc_device &dev, platform::stream_profile profile)
412  {
413  py::gil_scoped_release release;
414  dev.close(profile);
415  }, "profile"_a)
416  .def("set_power_state", &platform::multi_pins_uvc_device::set_power_state, "state"_a)
417  .def("get_power_state", &platform::multi_pins_uvc_device::get_power_state)
418  .def("init_xu", &platform::multi_pins_uvc_device::init_xu, "xu"_a)
419  .def("set_xu", [](platform::multi_pins_uvc_device &dev, const platform::extension_unit &xu, uint8_t ctrl, py::list l)
420  {
421  std::vector<uint8_t> data(l.size());
422  for (int i = 0; i < l.size(); ++i)
423  data[i] = l[i].cast<uint8_t>();
424  return dev.set_xu(xu, ctrl, data.data(), (int)data.size());
425  }, "xu"_a, "ctrl"_a, "data"_a)
426  .def("set_xu", [](platform::multi_pins_uvc_device &dev, const platform::extension_unit &xu, uint8_t ctrl, std::vector<uint8_t> &data)
427  {
428  return dev.set_xu(xu, ctrl, data.data(), (int)data.size());
429  }, "xu"_a, "ctrl"_a, "data"_a)
430  .def("get_xu", [](const platform::multi_pins_uvc_device &dev, const platform::extension_unit &xu, uint8_t ctrl, size_t len)
431  {
432  std::vector<uint8_t> data(len);
433  dev.get_xu(xu, ctrl, data.data(), (int)len);
434  py::list ret(len);
435  for (size_t i = 0; i < len; ++i)
436  ret[i] = data[i];
437  return ret;
438  }, "xu"_a, "ctrl"_a, "len"_a)
439  .def("get_xu_range", &platform::multi_pins_uvc_device::get_xu_range, "xu"_a, "ctrl"_a, "len"_a)
440  .def("get_pu", [](platform::multi_pins_uvc_device& dev, rs2_option opt) {
441  int val = 0;
442  dev.get_pu(opt, val);
443  return val;
444  }, "opt"_a)
445  .def("set_pu", &platform::multi_pins_uvc_device::set_pu, "opt"_a, "value"_a)
446  .def("get_pu_range", &platform::multi_pins_uvc_device::get_pu_range, "opt"_a)
447  .def("get_profiles", &platform::multi_pins_uvc_device::get_profiles)
450  .def("get_device_location", &platform::multi_pins_uvc_device::get_device_location);
451 
452 
453  /*py::enum_<command> command_py(m, "command");
454  command_py.value("enable_advanced_mode", command::enable_advanced_mode)
455  .value("advanced_mode_enabled", command::advanced_mode_enabled)
456  .value("reset", command::reset)
457  .value("set_advanced", command::set_advanced)
458  .value("get_advanced", command::get_advanced);*/
459 
460  m.def("create_backend", &platform::create_backend, py::return_value_policy::move);
461  m.def("encode_command", [](uint8_t opcode, uint32_t p1, uint32_t p2, uint32_t p3, uint32_t p4, py::list l)
462  {
463  std::vector<uint8_t> data(l.size());
464  for (int i = 0; i < l.size(); ++i)
465  data[i] = l[i].cast<uint8_t>();
466  return encode_command(static_cast<command>(opcode), p1, p2, p3, p4, data);
467  }, "opcode"_a, "p1"_a=0, "p2"_a=0, "p3"_a=0, "p4"_a=0, "data"_a = py::list(0));
468 }
469 
470 // Workaroud for failure to export template <typename T> class recordable
471 void librealsense::option::create_snapshot(std::shared_ptr<option>& snapshot) const {}
472 void librealsense::info_container::create_snapshot(std::shared_ptr<librealsense::info_interface> &) const {}
475 void librealsense::info_container::enable_recording(std::function<void(const info_interface&)> record_action){}
476 void librealsense::info_container::update(std::shared_ptr<extension_snapshot> ext){}
478 const std::string& librealsense::info_container::get_info(enum rs2_camera_info) const { static std::string s = ""; return s; }
479 std::vector<rs2_option> librealsense::options_container::get_supported_options(void)const { return{}; }
static const textual_icon lock
Definition: model-views.h:218
rs2_camera_info
Read-only strings that can be queried from the device. Not all information attributes are available o...
Definition: rs_sensor.h:22
GLboolean GLboolean g
GLint y
static const textual_icon unlock
Definition: model-views.h:237
bool set_xu(const extension_unit &xu, uint8_t ctrl, const uint8_t *data, int len) override
Definition: backend.h:710
GLuint const GLchar * name
rs2_option
Defines general configuration controls. These can generally be mapped to camera UVC controls...
Definition: rs_option.h:22
GLdouble s
void close(stream_profile profile) override
Definition: backend.h:407
GLfloat GLfloat p
Definition: glext.h:12687
platform::guid stoguid(std::string str)
const GLfloat * m
Definition: glext.h:6814
GLfloat value
#define BIND_RAW_RW_ARRAY(class, name, type, size)
void create_snapshot(std::shared_ptr< info_interface > &snapshot) const override
Definition: sensor.cpp:629
std::vector< uint8_t > encode_command(command opcode, uint32_t p1=0, uint32_t p2=0, uint32_t p3=0, uint32_t p4=0, std::vector< uint8_t > data=std::vector< uint8_t >())
virtual void create_snapshot(std::shared_ptr< option > &snapshot) const
Definition: option.cpp:30
GLdouble GLdouble GLdouble w
GLsizei const GLchar *const * string
GLfloat GLfloat GLfloat GLfloat h
Definition: glext.h:1960
GLdouble GLdouble z
GLdouble n
Definition: glext.h:1966
unsigned char uint8_t
Definition: stdint.h:78
bool get_xu(const extension_unit &xu, uint8_t ctrl, uint8_t *data, int len) const override
Definition: backend.h:439
std::shared_ptr< backend > create_backend()
GLenum GLuint id
GLuint index
GLenum GLsizei len
Definition: glext.h:3285
std::vector< rs2_option > get_supported_options() const override
Definition: option.cpp:197
GLuint GLfloat * val
def info(name, value, persistent=False)
Definition: test.py:301
GLdouble f
bool get_xu(const extension_unit &xu, uint8_t ctrl, uint8_t *data, int len) const override
Definition: backend.h:715
bool set_xu(const extension_unit &xu, uint8_t ctrl, const uint8_t *data, int len) override
Definition: backend.h:427
void register_info(rs2_camera_info info, const std::string &val)
Definition: sensor.cpp:602
void probe_and_commit(stream_profile profile, frame_callback callback, int buffers) override
Definition: backend.h:387
GLuint GLenum option
Definition: glext.h:5923
bool get_pu(rs2_option opt, int32_t &value) const override
Definition: backend.h:456
GLsizeiptr size
GLdouble x
unsigned int uint32_t
Definition: stdint.h:80
GLint GLsizei GLsizei height
void stream_on(std::function< void(const notification &n)> error_handler=[](const notification &n){}) override
Definition: backend.h:392
#define SNAME
Definition: pybackend.cpp:27
GLint GLint GLsizei GLint GLenum format
void probe_and_commit(stream_profile profile, frame_callback callback, int buffers) override
Definition: backend.h:654
def callback(frame)
Definition: t265_stereo.py:91
void init(void)
Definition: boing.c:180
void close(stream_profile profile) override
Definition: backend.h:685
void update(std::shared_ptr< extension_snapshot > ext) override
Definition: sensor.cpp:638
bool supports_info(rs2_camera_info info) const override
Definition: sensor.cpp:596
const base::type::char_t * unit
void update_info(rs2_camera_info info, const std::string &val)
Definition: sensor.cpp:614
const std::string & get_info(rs2_camera_info info) const override
Definition: sensor.cpp:621
#define NAME
Definition: pybackend.cpp:26
void enable_recording(std::function< void(const info_interface &)> record_action) override
Definition: sensor.cpp:633
bool get_pu(rs2_option opt, int32_t &value) const override
Definition: backend.h:725
GLfloat units
void next(auto_any_t cur, type2type< T, C > *)
Definition: foreach.hpp:757
void stream_on(std::function< void(const notification &n)> error_handler=[](const notification &n){}) override
Definition: backend.h:662
PYBIND11_MODULE(NAME, m)
Definition: pybackend.cpp:39
STBIWDEF int stbi_write_png(char const *filename, int w, int h, int comp, const void *data, int stride_in_bytes)
int min(int a, int b)
Definition: lz4s.c:73
typename::boost::move_detail::remove_reference< T >::type && move(T &&t) BOOST_NOEXCEPT
int i
GLboolean * data
double get_time()
Definition: rs_internal.hpp:62
Definition: parser.hpp:150
GLint GLsizei width


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