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" 11 py::class_<rs2::device>
device(m,
"device");
13 "sharing the same physical parent composite device.")
15 "sharing the same physical parent composite device. Identical to calling query_sensors.")
24 "like versions of various internal components",
"info"_a)
27 .def(
"__nonzero__", &rs2::device::operator
bool)
28 .def(
"__bool__", &rs2::device::operator
bool)
56 py::class_<rs2::updatable, rs2::device> updatable(m,
"updatable");
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.")
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>())
67 "Update an updatable device to the provided unsigned firmware. This call is executed on the caller's thread.",
"fw_image"_a,
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.",
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>());
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)
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>())
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>())
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>())
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>())
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",
111 py::gil_scoped_release gil;
112 self.trigger_device_calibration( type );
114 "Trigger the given calibration, if available",
"calibration_type"_a )
115 .def(
"register_calibration_change_callback",
118 self.register_calibration_change_callback(
126 py::gil_scoped_acquire gil;
131 std::cerr <<
"?!?!?!!? exception in python register_calibration_change_callback ?!?!?!?!?" << std::endl;
135 "Register (only once!) a callback that gets called for each change in calibration",
"callback"_a );
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",
143 self.register_calibration_change_callback(
151 py::gil_scoped_acquire gil;
156 std::cerr <<
"?!?!?!!? exception in python register_calibration_change_callback ?!?!?!?!?" << std::endl;
160 "Register (only once!) a callback that gets called for each change in calibration",
"callback"_a);
162 py::class_<rs2::debug_protocol> debug_protocol(m,
"debug_protocol");
163 debug_protocol.def(py::init<rs2::device>())
167 py::class_<rs2::device_list> device_list(m,
"device_list");
168 device_list.def(py::init<>())
171 if (i >=
self.
size())
172 throw py::index_error();
178 return py::make_iterator(
self.
begin(),
self.
end());
179 }, py::keep_alive<0, 1>())
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) {
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)
201 "loopback operation mode that uses the given file as input for raw data",
"filename"_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)
bool is_loopback_enabled() const
std::vector< sensor > query_sensors() const
void set_calibration_table(const calibration_table &calibration)
void set_intrinsics(int fisheye_sensor_id, const rs2_intrinsics &intrinsics)
void update_unsigned(const std::vector< uint8_t > &image, int update_mode=RS2_UNSIGNED_UPDATE_MODE_UPDATE) const
#define BIND_DOWNCAST(class, downcast)
GLsizei const GLchar *const * string
static const textual_icon stop
void reset_to_factory_calibration()
status
Defines return codes that SDK interfaces use. Negative values indicate errors, a zero value indicates...
void set_motion_device_intrinsics(rs2_stream stream_type, const rs2_motion_device_intrinsic &motion_intriniscs)
void init_device(py::module &m)
#define RS2_UNSIGNED_UPDATE_MODE_UPDATE
const char * get_info(rs2_camera_info info) const
std::vector< uint8_t > send_and_receive_raw_data(const std::vector< uint8_t > &input) const
calibration_table get_calibration_table()
void set_extrinsics(rs2_stream from_stream, int from_id, rs2_stream to_stream, int to_id, rs2_extrinsics &extrinsics)
bool supports(rs2_camera_info info) const
void write_calibration() const
std::vector< uint8_t > create_flash_backup() const
void enable_loopback(const std::string &from_file)
void enter_update_state() const
bool contains(const device &dev) const