pyrs_device.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 "python.hpp"
5 #include "../include/librealsense2/hpp/rs_internal.hpp"
6 #include "../include/librealsense2/hpp/rs_device.hpp"
7 #include "../include/librealsense2/hpp/rs_record_playback.hpp" // for downcasts
8 
9 void init_device(py::module &m) {
11  py::class_<rs2::device> device(m, "device"); // No docstring in C++
12  device.def("query_sensors", &rs2::device::query_sensors, "Returns the list of adjacent devices, "
13  "sharing the same physical parent composite device.")
14  .def_property_readonly("sensors", &rs2::device::query_sensors, "List of adjacent devices, "
15  "sharing the same physical parent composite device. Identical to calling query_sensors.")
16  .def("first_depth_sensor", [](rs2::device& self) { return self.first<rs2::depth_sensor>(); }) // No docstring in C++
17  .def("first_roi_sensor", [](rs2::device& self) { return self.first<rs2::roi_sensor>(); }) // No docstring in C++
18  .def("first_pose_sensor", [](rs2::device& self) { return self.first<rs2::pose_sensor>(); }) // No docstring in C++
19  .def("first_color_sensor", [](rs2::device& self) { return self.first<rs2::color_sensor>(); }) // No docstring in C++
20  .def("first_motion_sensor", [](rs2::device& self) { return self.first<rs2::motion_sensor>(); }) // No docstring in C++
21  .def("first_fisheye_sensor", [](rs2::device& self) { return self.first<rs2::fisheye_sensor>(); }) // No docstring in C++
22  .def("supports", &rs2::device::supports, "Check if specific camera info is supported.", "info"_a)
23  .def("get_info", &rs2::device::get_info, "Retrieve camera specific information, "
24  "like versions of various internal components", "info"_a)
25  .def("hardware_reset", &rs2::device::hardware_reset, "Send hardware reset request to the device")
26  .def(py::init<>())
27  .def("__nonzero__", &rs2::device::operator bool) // Called to implement truth value testing in Python 2
28  .def("__bool__", &rs2::device::operator bool) // Called to implement truth value testing in Python 3
29  .def(BIND_DOWNCAST(device, debug_protocol))
30  .def(BIND_DOWNCAST(device, playback))
31  .def(BIND_DOWNCAST(device, recorder))
32  .def(BIND_DOWNCAST(device, tm2))
33  .def(BIND_DOWNCAST(device, updatable))
34  .def(BIND_DOWNCAST(device, update_device))
35  .def(BIND_DOWNCAST(device, auto_calibrated_device))
36  .def(BIND_DOWNCAST(device, device_calibration))
37  .def(BIND_DOWNCAST(device, calibration_change_device))
38  .def(BIND_DOWNCAST(device, firmware_logger))
39  .def("__repr__", [](const rs2::device &self) {
40  std::stringstream ss;
41  ss << "<" SNAME ".device: " << self.get_info(RS2_CAMERA_INFO_NAME);
42  if (self.supports(RS2_CAMERA_INFO_SERIAL_NUMBER))
43  ss << " (S/N: " << self.get_info(RS2_CAMERA_INFO_SERIAL_NUMBER);
44  else
45  ss << " (FW update id: " << self.get_info(RS2_CAMERA_INFO_FIRMWARE_UPDATE_ID);
46  if (self.supports(RS2_CAMERA_INFO_FIRMWARE_VERSION))
47  ss << " FW: " << self.get_info(RS2_CAMERA_INFO_FIRMWARE_VERSION);
48  if (self.supports(RS2_CAMERA_INFO_CAMERA_LOCKED))
49  ss << " LOCKED: " << self.get_info(RS2_CAMERA_INFO_CAMERA_LOCKED);
50  ss << ")>";
51  return ss.str();
52  });
53 
54  // not binding update_progress_callback, templated
55 
56  py::class_<rs2::updatable, rs2::device> updatable(m, "updatable"); // No docstring in C++
57  updatable.def(py::init<rs2::device>())
58  .def("enter_update_state", &rs2::updatable::enter_update_state, "Move the device to update state, this will cause the updatable device to disconnect and reconnect as an update device.")
59  .def("create_flash_backup", (std::vector<uint8_t>(rs2::updatable::*)() const) &rs2::updatable::create_flash_backup,
60  "Create backup of camera flash memory. Such backup does not constitute valid firmware image, and cannot be "
61  "loaded back to the device, but it does contain all calibration and device information.", py::call_guard<py::gil_scoped_release>())
62  .def("create_flash_backup", [](rs2::updatable& self, std::function<void(float)> f) { return self.create_flash_backup(f); },
63  "Create backup of camera flash memory. Such backup does not constitute valid firmware image, and cannot be "
64  "loaded back to the device, but it does contain all calibration and device information.",
65  "callback"_a, py::call_guard<py::gil_scoped_release>())
66  .def("update_unsigned", (void(rs2::updatable::*)(const std::vector<uint8_t>&, int) const) &rs2::updatable::update_unsigned,
67  "Update an updatable device to the provided unsigned firmware. This call is executed on the caller's thread.", "fw_image"_a,
68  "update_mode"_a = RS2_UNSIGNED_UPDATE_MODE_UPDATE, py::call_guard<py::gil_scoped_release>())
69  .def("update_unsigned", [](rs2::updatable& self, const std::vector<uint8_t>& fw_image, std::function<void(float)> f, int update_mode) { return self.update_unsigned(fw_image, f, update_mode); },
70  "Update an updatable device to the provided unsigned firmware. This call is executed on the caller's thread and it supports progress notifications via the callback.",
71  "fw_image"_a, "callback"_a, "update_mode"_a = RS2_UNSIGNED_UPDATE_MODE_UPDATE, py::call_guard<py::gil_scoped_release>());
72 
73  py::class_<rs2::update_device, rs2::device> update_device(m, "update_device");
74  update_device.def(py::init<rs2::device>())
75  .def("update", [](rs2::update_device& self, const std::vector<uint8_t>& fw_image) { return self.update(fw_image); },
76  "Update an updatable device to the provided firmware. This call is executed on the caller's thread.", "fw_image"_a, py::call_guard<py::gil_scoped_release>())
77  .def("update", [](rs2::update_device& self, const std::vector<uint8_t>& fw_image, std::function<void(float)> f) { return self.update(fw_image, f); },
78  "Update an updatable device to the provided firmware. This call is executed on the caller's thread and it supports progress notifications via the callback.",
79  "fw_image"_a, "callback"_a, py::call_guard<py::gil_scoped_release>());
80 
81  py::class_<rs2::auto_calibrated_device, rs2::device> auto_calibrated_device(m, "auto_calibrated_device");
82  auto_calibrated_device.def(py::init<rs2::device>(), "device"_a)
83  .def("write_calibration", &rs2::auto_calibrated_device::write_calibration, "Write calibration that was set by set_calibration_table to device's EEPROM.", py::call_guard<py::gil_scoped_release>())
84  .def("run_on_chip_calibration", [](rs2::auto_calibrated_device& self, std::string json_content, int timeout_ms)
85  {
86  float health;
87  return py::make_tuple(self.run_on_chip_calibration(json_content, &health, timeout_ms), health);
88  },"This will improve the depth noise (plane fit RMS). This call is executed on the caller's thread.","json_content"_a, "timeout_ms"_a, py::call_guard<py::gil_scoped_release>())
89  .def("run_on_chip_calibration", [](rs2::auto_calibrated_device& self, std::string json_content, std::function<void(float)> f, int timeout_ms)
90  {
91  float health;
92  return py::make_tuple(self.run_on_chip_calibration(json_content, &health, f, timeout_ms), health);
93  },"This will improve the depth noise (plane fit RMS). This call is executed on the caller's thread and it supports progress notifications via the callback.", "json_content"_a, "callback"_a, "timeout_ms"_a, py::call_guard<py::gil_scoped_release>())
94  .def("run_tare_calibration", [](const rs2::auto_calibrated_device& self, float ground_truth_mm, std::string json_content, int timeout_ms)
95  {
96  return self.run_tare_calibration(ground_truth_mm, json_content, timeout_ms);
97  }, "This will adjust camera absolute distance to flat target. This call is executed on the caller's thread and it supports progress notifications via the callback.", "ground_truth_mm"_a, "json_content"_a, "timeout_ms"_a, py::call_guard<py::gil_scoped_release>())
98  .def("run_tare_calibration", [](const rs2::auto_calibrated_device& self, float ground_truth_mm, std::string json_content, std::function<void(float)> callback, int timeout_ms)
99  {
100  return self.run_tare_calibration(ground_truth_mm, json_content, callback, timeout_ms);
101  }, "This will adjust camera absolute distance to flat target. This call is executed on the caller's thread.", "ground_truth_mm"_a, "json_content"_a, "callback"_a, "timeout_ms"_a, py::call_guard<py::gil_scoped_release>())
102  .def("get_calibration_table", &rs2::auto_calibrated_device::get_calibration_table, "Read current calibration table from flash.")
103  .def("set_calibration_table", &rs2::auto_calibrated_device::set_calibration_table, "Set current table to dynamic area.")
104  .def("reset_to_factory_calibration", &rs2::auto_calibrated_device::reset_to_factory_calibration, "Reset device to factory calibration.");
105 
106  py::class_<rs2::device_calibration, rs2::device> device_calibration( m, "device_calibration" );
107  device_calibration.def( py::init<rs2::device>(), "device"_a )
108  .def( "trigger_device_calibration",
110  {
111  py::gil_scoped_release gil;
112  self.trigger_device_calibration( type );
113  },
114  "Trigger the given calibration, if available", "calibration_type"_a )
115  .def( "register_calibration_change_callback",
116  []( rs2::device_calibration& self, std::function<void( rs2_calibration_status )> callback )
117  {
118  self.register_calibration_change_callback(
120  {
121  try
122  {
123  // "When calling a C++ function from Python, the GIL is always held"
124  // -- since we're not being called from Python but instead are calling it,
125  // we need to acquire it to not have issues with other threads...
126  py::gil_scoped_acquire gil;
127  callback( status );
128  }
129  catch( ... )
130  {
131  std::cerr << "?!?!?!!? exception in python register_calibration_change_callback ?!?!?!?!?" << std::endl;
132  }
133  } );
134  },
135  "Register (only once!) a callback that gets called for each change in calibration", "callback"_a );
136 
137 
138  py::class_<rs2::calibration_change_device, rs2::device> calibration_change_device(m, "calibration_change_device");
139  calibration_change_device.def(py::init<rs2::device>(), "device"_a)
140  .def("register_calibration_change_callback",
141  [](rs2::calibration_change_device& self, std::function<void(rs2_calibration_status)> callback)
142  {
143  self.register_calibration_change_callback(
145  {
146  try
147  {
148  // "When calling a C++ function from Python, the GIL is always held"
149  // -- since we're not being called from Python but instead are calling it,
150  // we need to acquire it to not have issues with other threads...
151  py::gil_scoped_acquire gil;
152  callback(status);
153  }
154  catch (...)
155  {
156  std::cerr << "?!?!?!!? exception in python register_calibration_change_callback ?!?!?!?!?" << std::endl;
157  }
158  });
159  },
160  "Register (only once!) a callback that gets called for each change in calibration", "callback"_a);
161 
162  py::class_<rs2::debug_protocol> debug_protocol(m, "debug_protocol"); // No docstring in C++
163  debug_protocol.def(py::init<rs2::device>())
164  .def("send_and_receive_raw_data", &rs2::debug_protocol::send_and_receive_raw_data,
165  "input"_a); // No docstring in C++
166 
167  py::class_<rs2::device_list> device_list(m, "device_list"); // No docstring in C++
168  device_list.def(py::init<>())
169  .def("contains", &rs2::device_list::contains) // No docstring in C++
170  .def("__getitem__", [](const rs2::device_list& self, size_t i) {
171  if (i >= self.size())
172  throw py::index_error();
173  return self[uint32_t(i)];
174  })
175  .def("__len__", &rs2::device_list::size)
176  .def("size", &rs2::device_list::size) // No docstring in C++
177  .def("__iter__", [](const rs2::device_list& self) {
178  return py::make_iterator(self.begin(), self.end());
179  }, py::keep_alive<0, 1>())
180  .def("__getitem__", [](const rs2::device_list& self, py::slice slice) {
181  size_t start, stop, step, slicelength;
182  if (!slice.compute(self.size(), &start, &stop, &step, &slicelength))
183  throw py::error_already_set();
184  auto *dlist = new std::vector<rs2::device>(slicelength);
185  for (size_t i = 0; i < slicelength; ++i) {
186  (*dlist)[i] = self[uint32_t(start)];
187  start += step;
188  }
189  return dlist;
190  })
191  .def("front", &rs2::device_list::front) // No docstring in C++
192  .def("back", &rs2::device_list::back); // No docstring in C++
193 
194  py::class_<rs2::tm2, rs2::device> tm2(m, "tm2", "The tm2 class is an interface for T2XX devices, such as T265.\n"
195  "For T265, it provides RS2_STREAM_FISHEYE(2), RS2_STREAM_GYRO, "
196  "RS2_STREAM_ACCEL, and RS2_STREAM_POSE streams, and contains the following sensors:\n"
197  "-pose_sensor: map and relocalization functions.\n"
198  "-wheel_odometer: input for odometry data.");
199  tm2.def(py::init<rs2::device>(), "device"_a)
200  .def("enable_loopback", &rs2::tm2::enable_loopback, "Enter the given device into "
201  "loopback operation mode that uses the given file as input for raw data", "filename"_a)
202  .def("disable_loopback", &rs2::tm2::disable_loopback, "Restores the given device into normal operation mode")
203  .def("is_loopback_enabled", &rs2::tm2::is_loopback_enabled, "Checks if the device is in loopback mode or not")
204  .def("set_intrinsics", &rs2::tm2::set_intrinsics, "Set camera intrinsics", "sensor_id"_a, "intrinsics"_a)
205  .def("set_extrinsics", &rs2::tm2::set_extrinsics, "Set camera extrinsics", "from_stream"_a, "from_id"_a, "to_stream"_a, "to_id"_a, "extrinsics"_a)
206  .def("set_motion_device_intrinsics", &rs2::tm2::set_motion_device_intrinsics, "Set motion device intrinsics", "stream_type"_a, "motion_intrinsics"_a)
207  .def("reset_to_factory_calibration", &rs2::tm2::reset_to_factory_calibration, "Reset to factory calibration")
208  .def("write_calibration", &rs2::tm2::write_calibration, "Write calibration to device's EEPROM");
209 
211 }
GLuint GLuint end
bool is_loopback_enabled() const
Definition: rs_device.hpp:826
rs2_calibration_type
Definition: rs_device.h:344
std::vector< sensor > query_sensors() const
Definition: rs_device.hpp:25
device front() const
Definition: rs_device.hpp:719
const GLfloat * m
Definition: glext.h:6814
void set_calibration_table(const calibration_table &calibration)
Definition: rs_device.hpp:546
void set_intrinsics(int fisheye_sensor_id, const rs2_intrinsics &intrinsics)
Definition: rs_device.hpp:861
uint32_t size() const
Definition: rs_device.hpp:711
void update_unsigned(const std::vector< uint8_t > &image, int update_mode=RS2_UNSIGNED_UPDATE_MODE_UPDATE) const
Definition: rs_device.hpp:233
#define BIND_DOWNCAST(class, downcast)
Definition: python.hpp:33
GLsizei const GLchar *const * string
static const textual_icon stop
Definition: model-views.h:225
void reset_to_factory_calibration()
Definition: rs_device.hpp:307
status
Defines return codes that SDK interfaces use. Negative values indicate errors, a zero value indicates...
not_this_one begin(...)
GLdouble f
void set_motion_device_intrinsics(rs2_stream stream_type, const rs2_motion_device_intrinsic &motion_intriniscs)
Definition: rs_device.hpp:891
GLsizeiptr size
void init_device(py::module &m)
Definition: pyrs_device.cpp:9
#define RS2_UNSIGNED_UPDATE_MODE_UPDATE
Definition: rs_device.h:206
rs2_calibration_status
Definition: rs_device.h:356
unsigned int uint32_t
Definition: stdint.h:80
void hardware_reset()
Definition: rs_device.hpp:90
const char * get_info(rs2_camera_info info) const
Definition: rs_device.hpp:79
#define SNAME
Definition: pybackend.cpp:27
def callback(frame)
Definition: t265_stereo.py:91
GLuint start
std::vector< uint8_t > send_and_receive_raw_data(const std::vector< uint8_t > &input) const
Definition: rs_device.hpp:649
calibration_table get_calibration_table()
Definition: rs_device.hpp:522
void set_extrinsics(rs2_stream from_stream, int from_id, rs2_stream to_stream, int to_id, rs2_extrinsics &extrinsics)
Definition: rs_device.hpp:877
device back() const
Definition: rs_device.hpp:720
bool supports(rs2_camera_info info) const
Definition: rs_device.hpp:66
void write_calibration() const
Definition: rs_device.hpp:297
std::vector< uint8_t > create_flash_backup() const
Definition: rs_device.hpp:191
GLenum type
std::ostream & cerr()
int i
void enable_loopback(const std::string &from_file)
Definition: rs_device.hpp:805
void disable_loopback()
Definition: rs_device.hpp:815
void enter_update_state() const
Definition: rs_device.hpp:182
auto device
Definition: pyrs_net.cpp:17
bool contains(const device &dev) const
Definition: rs_device.hpp:686


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