5 #include "../include/librealsense2/hpp/rs_sensor.hpp" 11 py::class_<rs2::notification> notification(m,
"notification");
12 notification.def(py::init<>())
14 "Retrieve the notification's category.")
16 "The notification's category. Identical to calling get_category.")
18 "Retrieve the notification's description.")
20 "The notification's description. Identical to calling get_description.")
22 "Retrieve the notification's arrival timestamp.")
24 "The notification's arrival timestamp. Identical to calling get_timestamp.")
26 "Retrieve the notification's severity.")
28 "The notification's severity. Identical to calling get_severity.")
30 "Retrieve the notification's serialized data.")
32 "The notification's serialized data. Identical to calling get_serialized_data.")
39 py::class_<rs2::sensor, rs2::options>
sensor(m,
"sensor");
41 "Open sensor for exclusive access, by commiting to a configuration",
"profile"_a)
43 "Check if specific camera info is supported.",
"info")
45 "Check if specific camera info is supported.",
"info")
47 "like versions of various internal components.",
"info"_a)
49 self.set_notifications_callback(
callback);
50 },
"Register Notifications callback",
"callback"_a)
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>())
57 },
"Start passing frames into user provided callback.",
"callback"_a)
60 },
"Start passing frames into user provided syncer.",
"syncer"_a)
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>())
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")
70 .def(
"__nonzero__", &rs2::sensor::operator
bool)
71 .def(
"__bool__", &rs2::sensor::operator
bool)
85 py::class_<rs2::roi_sensor, rs2::sensor> roi_sensor(m,
"roi_sensor");
86 roi_sensor.def(py::init<rs2::sensor>(),
"sensor"_a)
90 py::class_<rs2::depth_sensor, rs2::sensor>
depth_sensor(m,
"depth_sensor");
91 depth_sensor.def(py::init<rs2::sensor>(),
"sensor"_a)
93 "Retrieves mapping between the units of the depth image and meters.");
95 py::class_<rs2::color_sensor, rs2::sensor>
color_sensor(m,
"color_sensor");
96 color_sensor.def(py::init<rs2::sensor>(),
"sensor"_a);
98 py::class_<rs2::motion_sensor, rs2::sensor> motion_sensor(m,
"motion_sensor");
99 motion_sensor.def(py::init<rs2::sensor>(),
"sensor"_a);
101 py::class_<rs2::fisheye_sensor, rs2::sensor> fisheye_sensor(m,
"fisheye_sensor");
102 fisheye_sensor.def(py::init<rs2::sensor>(),
"sensor"_a);
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",
109 py::call_guard< py::gil_scoped_release >())
110 .def(
"override_extrinsics",
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",
120 py::call_guard< py::gil_scoped_release >())
121 .def(
"reset_calibration",
123 py::call_guard< py::gil_scoped_release >());
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 >());
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 >() );
138 py::class_<rs2::depth_stereo_sensor, rs2::depth_sensor> depth_stereo_sensor(m,
"depth_stereo_sensor");
139 depth_stereo_sensor.def(py::init<rs2::sensor>())
142 py::class_<rs2::pose_sensor, rs2::sensor>
pose_sensor(m,
"pose_sensor");
143 pose_sensor.def(py::init<rs2::sensor>(),
"sensor"_a)
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)
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().")
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)
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).",
172 "Removes a named virtual landmark in the current map, known as static node.\n" 174 .def(
"__nonzero__", &rs2::pose_sensor::operator
bool)
175 .def(
"__bool__", &rs2::pose_sensor::operator
bool);
177 py::class_<rs2::wheel_odometer, rs2::sensor>
wheel_odometer(m,
"wheel_odometer");
178 wheel_odometer.def(py::init<rs2::sensor>(),
"sensor"_a)
180 "Load Wheel odometer settings from host to device.",
"odometry_config_buf"_a)
182 "Send wheel odometry data for each individual sensor (wheel)",
183 "wo_sensor_id"_a,
"frame_num"_a,
"translational_velocity"_a);
std::vector< uint8_t > export_localization_map() const
rs2_camera_info
Read-only strings that can be queried from the device. Not all information attributes are available o...
float get_depth_scale() const
std::string get_serialized_data() const
void init_sensor(py::module &m)
rs2_option
Defines general configuration controls. These can generally be mapped to camera UVC controls...
std::vector< stream_profile > get_active_streams() const
void override_intrinsics(rs2_intrinsics const &intr)
std::vector< filter > get_recommended_filters() const
rs2_log_severity get_severity() const
float get_max_usable_depth_range() const
#define BIND_DOWNCAST(class, downcast)
GLsizei const GLchar *const * string
std::string get_description() const
void set_region_of_interest(const region_of_interest &roi)
Quaternion used to represent rotation.
region_of_interest get_region_of_interest() const
float get_stereo_baseline() const
rs2_dsm_params get_dsm_params() const
bool supports(rs2_camera_info info) const
bool supports(rs2_option option) const
rs2_notification_category get_category() const
std::vector< stream_profile > get_debug_stream_profiles() const
bool load_wheel_odometery_config(const std::vector< uint8_t > &odometry_config_buf) const
void override_extrinsics(rs2_extrinsics const &extr)
3D vector in Euclidean coordinate space
bool set_static_node(const std::string &guid, const rs2_vector &pos, const rs2_quaternion &orient) const
bool import_localization_map(const std::vector< uint8_t > &lmap_buf) const
void open(const stream_profile &profile) const
double get_timestamp() const
bool send_wheel_odometry(uint8_t wo_sensor_id, uint32_t frame_num, const rs2_vector &translational_velocity)
const char * get_info(rs2_camera_info info) const
bool remove_static_node(const std::string &guid) const
std::vector< stream_profile > get_stream_profiles() const
void override_dsm_params(rs2_dsm_params const ¶ms)