pyrs_sensor.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_sensor.hpp"
6 #include "calibrated-sensor.h"
8 
9 void init_sensor(py::module &m) {
11  py::class_<rs2::notification> notification(m, "notification"); // No docstring in C++
12  notification.def(py::init<>())
13  .def("get_category", &rs2::notification::get_category,
14  "Retrieve the notification's category.")
15  .def_property_readonly("category", &rs2::notification::get_category,
16  "The notification's category. Identical to calling get_category.")
17  .def("get_description", &rs2::notification::get_description,
18  "Retrieve the notification's description.")
19  .def_property_readonly("description", &rs2::notification::get_description,
20  "The notification's description. Identical to calling get_description.")
21  .def("get_timestamp", &rs2::notification::get_timestamp,
22  "Retrieve the notification's arrival timestamp.")
23  .def_property_readonly("timestamp", &rs2::notification::get_timestamp,
24  "The notification's arrival timestamp. Identical to calling get_timestamp.")
25  .def("get_severity", &rs2::notification::get_severity,
26  "Retrieve the notification's severity.")
27  .def_property_readonly("severity", &rs2::notification::get_severity,
28  "The notification's severity. Identical to calling get_severity.")
29  .def("get_serialized_data", &rs2::notification::get_severity,
30  "Retrieve the notification's serialized data.")
31  .def_property_readonly("serialized_data", &rs2::notification::get_serialized_data,
32  "The notification's serialized data. Identical to calling get_serialized_data.")
33  .def("__repr__", [](const rs2::notification &n) {
34  return n.get_description();
35  });
36 
37  // not binding notifications_callback, templated
38 
39  py::class_<rs2::sensor, rs2::options> sensor(m, "sensor"); // No docstring in C++
40  sensor.def("open", (void (rs2::sensor::*)(const rs2::stream_profile&) const) &rs2::sensor::open,
41  "Open sensor for exclusive access, by commiting to a configuration", "profile"_a)
42  .def("supports", (bool (rs2::sensor::*)(rs2_camera_info) const) &rs2::sensor::supports,
43  "Check if specific camera info is supported.", "info")
44  .def("supports", (bool (rs2::sensor::*)(rs2_option) const) &rs2::options::supports,
45  "Check if specific camera info is supported.", "info")
46  .def("get_info", &rs2::sensor::get_info, "Retrieve camera specific information, "
47  "like versions of various internal components.", "info"_a)
48  .def("set_notifications_callback", [](const rs2::sensor& self, std::function<void(rs2::notification)> callback) {
49  self.set_notifications_callback(callback);
50  }, "Register Notifications callback", "callback"_a)
51  .def("open", (void (rs2::sensor::*)(const std::vector<rs2::stream_profile>&) const) &rs2::sensor::open,
52  "Open sensor for exclusive access, by committing to a composite configuration, specifying one or "
53  "more stream profiles.", "profiles"_a)
54  .def("close", &rs2::sensor::close, "Close sensor for exclusive access.", py::call_guard<py::gil_scoped_release>())
55  .def("start", [](const rs2::sensor& self, std::function<void(rs2::frame)> callback) {
56  self.start(callback);
57  }, "Start passing frames into user provided callback.", "callback"_a)
58  .def("start", [](const rs2::sensor& self, rs2::syncer& syncer) {
59  self.start(syncer);
60  }, "Start passing frames into user provided syncer.", "syncer"_a)
61  .def("start", [](const rs2::sensor& self, rs2::frame_queue& queue) {
62  self.start(queue);
63  }, "start passing frames into specified frame_queue", "queue"_a)
64  .def("stop", &rs2::sensor::stop, "Stop streaming.", py::call_guard<py::gil_scoped_release>())
65  .def("get_stream_profiles", &rs2::sensor::get_stream_profiles, "Retrieves the list of stream profiles supported by the sensor.")
66  .def("get_active_streams", &rs2::sensor::get_active_streams, "Retrieves the list of stream profiles currently streaming on the sensor.")
67  .def_property_readonly("profiles", &rs2::sensor::get_stream_profiles, "The list of stream profiles supported by the sensor. Identical to calling get_stream_profiles")
68  .def("get_recommended_filters", &rs2::sensor::get_recommended_filters, "Return the recommended list of filters by the sensor.")
69  .def(py::init<>())
70  .def("__nonzero__", &rs2::sensor::operator bool) // Called to implement truth value testing in Python 2
71  .def("__bool__", &rs2::sensor::operator bool) // Called to implement truth value testing in Python 3
72  .def(BIND_DOWNCAST(sensor, roi_sensor))
73  .def(BIND_DOWNCAST(sensor, depth_sensor))
74  .def(BIND_DOWNCAST(sensor, color_sensor))
75  .def(BIND_DOWNCAST(sensor, motion_sensor))
76  .def(BIND_DOWNCAST(sensor, fisheye_sensor))
77  .def(BIND_DOWNCAST(sensor, pose_sensor))
78  .def(BIND_DOWNCAST(sensor, calibrated_sensor))
79  .def(BIND_DOWNCAST(sensor, wheel_odometer))
80  .def(BIND_DOWNCAST(sensor, max_usable_range_sensor))
81  .def(BIND_DOWNCAST(sensor, debug_stream_sensor));
82  // rs2::sensor_from_frame [frame.def("get_sensor", ...)?
83  // rs2::sensor==sensor?
84 
85  py::class_<rs2::roi_sensor, rs2::sensor> roi_sensor(m, "roi_sensor"); // No docstring in C++
86  roi_sensor.def(py::init<rs2::sensor>(), "sensor"_a)
87  .def("set_region_of_interest", &rs2::roi_sensor::set_region_of_interest, "roi"_a) // No docstring in C++
88  .def("get_region_of_interest", &rs2::roi_sensor::get_region_of_interest); // No docstring in C++
89 
90  py::class_<rs2::depth_sensor, rs2::sensor> depth_sensor(m, "depth_sensor"); // No docstring in C++
91  depth_sensor.def(py::init<rs2::sensor>(), "sensor"_a)
92  .def("get_depth_scale", &rs2::depth_sensor::get_depth_scale,
93  "Retrieves mapping between the units of the depth image and meters.");
94 
95  py::class_<rs2::color_sensor, rs2::sensor> color_sensor(m, "color_sensor"); // No docstring in C++
96  color_sensor.def(py::init<rs2::sensor>(), "sensor"_a);
97 
98  py::class_<rs2::motion_sensor, rs2::sensor> motion_sensor(m, "motion_sensor"); // No docstring in C++
99  motion_sensor.def(py::init<rs2::sensor>(), "sensor"_a);
100 
101  py::class_<rs2::fisheye_sensor, rs2::sensor> fisheye_sensor(m, "fisheye_sensor"); // No docstring in C++
102  fisheye_sensor.def(py::init<rs2::sensor>(), "sensor"_a);
103 
104  py::class_<rs2::calibrated_sensor, rs2::sensor> cal_sensor( m, "calibrated_sensor" );
105  cal_sensor.def(py::init<rs2::sensor>(), "sensor"_a)
106  .def("override_intrinsics",
108  "intrinsics"_a,
109  py::call_guard< py::gil_scoped_release >())
110  .def("override_extrinsics",
112  "extrinsics"_a,
113  py::call_guard< py::gil_scoped_release >())
114  .def("get_dsm_params",
116  py::call_guard< py::gil_scoped_release >())
117  .def("override_dsm_params",
119  "dsm_params"_a,
120  py::call_guard< py::gil_scoped_release >())
121  .def("reset_calibration",
123  py::call_guard< py::gil_scoped_release >());
124 
125  py::class_<rs2::max_usable_range_sensor, rs2::sensor> mur_sensor(m, "max_usable_range_sensor");
126  mur_sensor.def(py::init<rs2::sensor>(), "sensor"_a)
127  .def("get_max_usable_depth_range",
129  py::call_guard< py::gil_scoped_release >());
130 
131  py::class_< rs2::debug_stream_sensor, rs2::sensor > ds_sensor( m, "debug_stream_sensor" );
132  ds_sensor.def( py::init< rs2::sensor >(), "sensor"_a )
133  .def( "get_debug_stream_profiles",
135  py::call_guard< py::gil_scoped_release >() );
136 
137  // rs2::depth_stereo_sensor
138  py::class_<rs2::depth_stereo_sensor, rs2::depth_sensor> depth_stereo_sensor(m, "depth_stereo_sensor"); // No docstring in C++
139  depth_stereo_sensor.def(py::init<rs2::sensor>())
140  .def("get_stereo_baseline", &rs2::depth_stereo_sensor::get_stereo_baseline, "Retrieve the stereoscopic baseline value from the sensor.");
141 
142  py::class_<rs2::pose_sensor, rs2::sensor> pose_sensor(m, "pose_sensor"); // No docstring in C++
143  pose_sensor.def(py::init<rs2::sensor>(), "sensor"_a)
144  .def("import_localization_map", &rs2::pose_sensor::import_localization_map,
145  "Load relocalization map onto device. Only one relocalization map can be imported at a time; "
146  "any previously existing map will be overwritten.\n"
147  "The imported map exists simultaneously with the map created during the most recent tracking "
148  "session after start(),"
149  "and they are merged after the imported map is relocalized.\n"
150  "This operation must be done before start().", "lmap_buf"_a)
151  .def("export_localization_map", &rs2::pose_sensor::export_localization_map,
152  "Get relocalization map that is currently on device, created and updated during most "
153  "recent tracking session.\n"
154  "Can be called before or after stop().")
155  .def("set_static_node", &rs2::pose_sensor::set_static_node,
156  "Creates a named virtual landmark in the current map, known as static node.\n"
157  "The static node's pose is provided relative to the origin of current coordinate system of device poses.\n"
158  "This function fails if the current tracker confidence is below 3 (high confidence).",
159  "guid"_a, "pos"_a, "orient"_a)
160  .def("get_static_node", [](const rs2::pose_sensor& self, const std::string& guid) {
161  rs2_vector pos;
162  rs2_quaternion orient;
163  bool res = self.get_static_node(guid, pos, orient);
164  return std::make_tuple(res, pos, orient);
165  }, "Gets the current pose of a static node that was created in the current map or in an imported map.\n"
166  "Static nodes of imported maps are available after relocalizing the imported map.\n"
167  "The static node's pose is returned relative to the current origin of coordinates of device poses.\n"
168  "Thus, poses of static nodes of an imported map are consistent with current device poses after relocalization.\n"
169  "This function fails if the current tracker confidence is below 3 (high confidence).",
170  "guid"_a)
171  .def("remove_static_node", &rs2::pose_sensor::remove_static_node,
172  "Removes a named virtual landmark in the current map, known as static node.\n"
173  "guid"_a)
174  .def("__nonzero__", &rs2::pose_sensor::operator bool) // Called to implement truth value testing in Python 2
175  .def("__bool__", &rs2::pose_sensor::operator bool); // Called to implement truth value testing in Python 3
176 
177  py::class_<rs2::wheel_odometer, rs2::sensor> wheel_odometer(m, "wheel_odometer"); // No docstring in C++
178  wheel_odometer.def(py::init<rs2::sensor>(), "sensor"_a)
179  .def("load_wheel_odometery_config", &rs2::wheel_odometer::load_wheel_odometery_config,
180  "Load Wheel odometer settings from host to device.", "odometry_config_buf"_a)
181  .def("send_wheel_odometry", &rs2::wheel_odometer::send_wheel_odometry,
182  "Send wheel odometry data for each individual sensor (wheel)",
183  "wo_sensor_id"_a, "frame_num"_a, "translational_velocity"_a);
185 }
std::vector< uint8_t > export_localization_map() const
Definition: rs_sensor.hpp:547
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
float get_depth_scale() const
Definition: rs_sensor.hpp:471
std::string get_serialized_data() const
Definition: rs_sensor.hpp:73
void init_sensor(py::module &m)
Definition: pyrs_sensor.cpp:9
rs2_option
Defines general configuration controls. These can generally be mapped to camera UVC controls...
Definition: rs_option.h:22
std::vector< stream_profile > get_active_streams() const
Definition: rs_sensor.hpp:246
const GLfloat * m
Definition: glext.h:6814
void override_intrinsics(rs2_intrinsics const &intr)
Definition: rs_sensor.hpp:683
std::vector< filter > get_recommended_filters() const
Definition: rs_sensor.hpp:273
rs2_log_severity get_severity() const
Definition: rs_sensor.hpp:64
float get_max_usable_depth_range() const
Definition: rs_sensor.hpp:747
#define BIND_DOWNCAST(class, downcast)
Definition: python.hpp:33
GLsizei const GLchar *const * string
std::string get_description() const
Definition: rs_sensor.hpp:46
GLdouble n
Definition: glext.h:1966
void set_region_of_interest(const region_of_interest &roi)
Definition: rs_sensor.hpp:435
Quaternion used to represent rotation.
Definition: rs_types.h:135
region_of_interest get_region_of_interest() const
Definition: rs_sensor.hpp:442
float get_stereo_baseline() const
Definition: rs_sensor.hpp:499
rs2_dsm_params get_dsm_params() const
Definition: rs_sensor.hpp:699
def callback(frame)
Definition: t265_stereo.py:91
bool supports(rs2_camera_info info) const
Definition: rs_sensor.hpp:125
bool supports(rs2_option option) const
Definition: rs_options.hpp:19
rs2_notification_category get_category() const
Definition: rs_sensor.hpp:38
std::vector< stream_profile > get_debug_stream_profiles() const
Definition: rs_sensor.hpp:776
bool load_wheel_odometery_config(const std::vector< uint8_t > &odometry_config_buf) const
Definition: rs_sensor.hpp:640
void override_extrinsics(rs2_extrinsics const &extr)
Definition: rs_sensor.hpp:691
3D vector in Euclidean coordinate space
Definition: rs_types.h:129
bool set_static_node(const std::string &guid, const rs2_vector &pos, const rs2_quaternion &orient) const
Definition: rs_sensor.hpp:578
bool import_localization_map(const std::vector< uint8_t > &lmap_buf) const
Definition: rs_sensor.hpp:534
void open(const stream_profile &profile) const
Definition: rs_sensor.hpp:111
float rs2_vector::* pos
double get_timestamp() const
Definition: rs_sensor.hpp:55
bool send_wheel_odometry(uint8_t wo_sensor_id, uint32_t frame_num, const rs2_vector &translational_velocity)
Definition: rs_sensor.hpp:654
GLuint res
Definition: glext.h:8856
void close() const
Definition: rs_sensor.hpp:173
const char * get_info(rs2_camera_info info) const
Definition: rs_sensor.hpp:138
bool remove_static_node(const std::string &guid) const
Definition: rs_sensor.hpp:610
std::vector< stream_profile > get_stream_profiles() const
Definition: rs_sensor.hpp:219
void stop() const
Definition: rs_sensor.hpp:195
void override_dsm_params(rs2_dsm_params const &params)
Definition: rs_sensor.hpp:711


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