5 #include "../include/librealsense2/hpp/rs_processing.hpp" 9 py::class_<rs2::frame_source> frame_source(m,
"frame_source",
"The source used to generate frames, which is usually done by the low level driver for each sensor. " 10 "frame_source is one of the parameters of processing_block's callback function, which can be used to re-generate the " 11 "frame and via frame_ready invoke another callback function to notify application frame is ready.");
13 "profile"_a,
"original"_a,
"new_bpp"_a = 0,
"new_width"_a = 0,
20 "Allocate composite frame with given params",
"frames"_a)
22 "callback funtion informing the frame is ready.",
"result"_a);
26 py::class_<rs2::frame_queue> frame_queue(m,
"frame_queue",
"Frame queues are the simplest cross-platform " 27 "synchronization primitive provided by librealsense to help " 28 "developers who are not using async APIs.");
29 frame_queue.def(py::init<>())
30 .def(py::init<unsigned int, bool>(),
"capacity"_a,
"keep_frames"_a =
false)
33 "becomes available in the queue and dequeue it.",
"timeout_ms"_a = 5000, py::call_guard<py::gil_scoped_release>())
36 self.poll_for_frame(&frame);
38 },
"Poll if a new frame is available and dequeue it if it is")
39 .def(
"try_wait_for_frame", [](
const rs2::frame_queue &
self,
unsigned int timeout_ms) {
41 auto success =
self.try_wait_for_frame(&frame, timeout_ms);
42 return std::make_tuple(
success, frame);
43 },
"timeout_ms"_a = 5000, py::call_guard<py::gil_scoped_release>())
44 .def(
"__call__", &rs2::frame_queue::operator(),
"Identical to calling enqueue.",
"f"_a)
48 py::class_<rs2::processing_block, rs2::options> processing_block(m,
"processing_block",
"Define the processing block workflow, inherit this class to " 49 "generate your own processing_block.");
52 }),
"processing_function"_a)
55 },
"Start the processing block with callback function to inform the application the frame is processed.",
"callback"_a)
62 py::class_<rs2::filter, rs2::processing_block, rs2::filter_interface>
filter(m,
"filter",
"Define the filter workflow, inherit this class to generate your own filter.");
64 return new rs2::filter(filter_function, queue_size);
65 }),
"filter_function"_a,
"queue_size"_a = 1)
76 .def(
"__nonzero__", &rs2::filter::operator
bool)
77 .def(
"__bool__", &rs2::filter::operator
bool);
81 py::class_<rs2::pointcloud, rs2::filter>
pointcloud(m,
"pointcloud",
"Generates 3D point clouds based on a depth frame. Can also map textures from a color frame.");
82 pointcloud.def(py::init<>())
83 .def(py::init<rs2_stream, int>(),
"stream"_a,
"index"_a = 0)
87 py::class_<rs2::yuy_decoder, rs2::filter> yuy_decoder(m,
"yuy_decoder",
"Converts frames in raw YUY format to RGB. This conversion is somewhat costly, " 88 "but the SDK will automatically try to use SSE2, AVX, or CUDA instructions where available to " 89 "get better performance. Othere implementations (GLSL, OpenCL, Neon, NCS) should follow.");
90 yuy_decoder.def(py::init<>());
92 py::class_<rs2::threshold_filter, rs2::filter> threshold(m,
"threshold_filter",
"Depth thresholding filter. By controlling min and " 93 "max options on the block, one could filter out depth values that are either too large " 94 "or too small, as a software post-processing step");
95 threshold.def(py::init<float, float>(),
"min_dist"_a = 0.15
f,
"max_dist"_a = 4.
f);
97 py::class_<rs2::units_transform, rs2::filter> units_transform(m,
"units_transform");
98 units_transform.def(py::init<>());
102 py::class_<rs2::syncer> syncer(m,
"syncer",
"Sync instance to align frames from different streams");
103 syncer.def(py::init<int>(),
"queue_size"_a = 1)
105 "of frames becomes available",
"timeout_ms"_a = 5000, py::call_guard<py::gil_scoped_release>())
106 .def(
"poll_for_frames", [](
const rs2::syncer &
self) {
108 self.poll_for_frames(&frames);
110 },
"Check if a coherent set of frames is available")
111 .def(
"try_wait_for_frames", [](
const rs2::syncer &
self,
unsigned int timeout_ms) {
113 auto success =
self.try_wait_for_frames(&fs, timeout_ms);
114 return std::make_tuple(
success, fs);
115 },
"timeout_ms"_a = 5000, py::call_guard<py::gil_scoped_release>());
118 py::class_<rs2::align, rs2::filter>
align(m,
"align",
"Performs alignment between depth image and another image.");
119 align.def(py::init<rs2_stream>(),
"To perform alignment of a depth image to the other, set the align_to parameter with the other stream type.\n" 120 "To perform alignment of a non depth image to a depth image, set the align_to parameter to RS2_STREAM_DEPTH.\n" 121 "Camera calibration and frame's stream type are determined on the fly, according to the first valid frameset passed to process().",
"align_to"_a)
124 py::class_<rs2::colorizer, rs2::filter>
colorizer(m,
"colorizer",
"Colorizer filter generates color images based on input depth frame");
125 colorizer.def(py::init<>())
126 .def(py::init<float>(),
"Possible values for color_scheme:\n" 135 "8 - Pattern",
"color_scheme"_a)
139 py::class_<rs2::decimation_filter, rs2::filter> decimation_filter(m,
"decimation_filter",
"Performs downsampling by using the median with specific kernel size.");
140 decimation_filter.def(py::init<>())
141 .def(py::init<float>(),
"magnitude"_a);
143 py::class_<rs2::temporal_filter, rs2::filter> temporal_filter(m,
"temporal_filter",
"Temporal filter smooths the image by calculating multiple frames " 144 "with alpha and delta settings. Alpha defines the weight of current frame, and delta defines the" 145 "threshold for edge classification and preserving.");
146 temporal_filter.def(py::init<>())
147 .def(py::init<float, float, int>(),
"Possible values for persistence_control:\n" 148 "1 - Valid in 8/8 - Persistency activated if the pixel was valid in 8 out of the last 8 frames\n" 149 "2 - Valid in 2 / last 3 - Activated if the pixel was valid in two out of the last 3 frames\n" 150 "3 - Valid in 2 / last 4 - Activated if the pixel was valid in two out of the last 4 frames\n" 151 "4 - Valid in 2 / 8 - Activated if the pixel was valid in two out of the last 8 frames\n" 152 "5 - Valid in 1 / last 2 - Activated if the pixel was valid in one of the last two frames\n" 153 "6 - Valid in 1 / last 5 - Activated if the pixel was valid in one out of the last 5 frames\n" 154 "7 - Valid in 1 / last 8 - Activated if the pixel was valid in one out of the last 8 frames\n" 155 "8 - Persist Indefinitely - Persistency will be imposed regardless of the stored history(most aggressive filtering)",
156 "smooth_alpha"_a,
"smooth_delta"_a,
"persistence_control"_a);
158 py::class_<rs2::spatial_filter, rs2::filter> spatial_filter(m,
"spatial_filter",
"Spatial filter smooths the image by calculating frame with alpha and delta settings. " 159 "Alpha defines the weight of the current pixel for smoothing, and is bounded within [25..100]%. Delta " 160 "defines the depth gradient below which the smoothing will occur as number of depth levels.");
161 spatial_filter.def(py::init<>())
162 .def(py::init<float, float, float, float>(),
"smooth_alpha"_a,
"smooth_delta"_a,
"magnitude"_a,
"hole_fill"_a);;
164 py::class_<rs2::disparity_transform, rs2::filter> disparity_transform(m,
"disparity_transform",
"Converts from depth representation " 165 "to disparity representation and vice - versa in depth frames");
166 disparity_transform.def(py::init<bool>(),
"transform_to_disparity"_a =
true);
168 py::class_<rs2::zero_order_invalidation, rs2::filter>
zero_order_invalidation(m,
"zero_order_invalidation",
"Fixes the zero order artifact");
169 zero_order_invalidation.def(py::init<>());
171 py::class_<rs2::hole_filling_filter, rs2::filter> hole_filling_filter(m,
"hole_filling_filter",
"The processing performed depends on the selected hole filling mode.");
172 hole_filling_filter.def(py::init<>())
173 .def(py::init<int>(),
"Possible values for mode:\n" 174 "0 - fill_from_left - Use the value from the left neighbor pixel to fill the hole\n" 175 "1 - farest_from_around - Use the value from the neighboring pixel which is furthest away from the sensor\n" 176 "2 - nearest_from_around - -Use the value from the neighboring pixel closest to the sensor",
"mode"_a);
178 py::class_<rs2::depth_huffman_decoder, rs2::filter> depth_huffman_decoder(m,
"depth_huffman_decoder",
"Decompresses Huffman-encoded Depth frame to standartized Z16 format");
179 depth_huffman_decoder.def(py::init<>());
181 py::class_<rs2::hdr_merge, rs2::filter> hdr_merge(m,
"hdr_merge",
"Merges depth frames with different sequence ID");
182 hdr_merge.def(py::init<>());
184 py::class_<rs2::sequence_id_filter, rs2::filter> sequence_id_filter(m,
"sequence_id_filter",
"Splits depth frames with different sequence ID");
185 sequence_id_filter.def(py::init<>())
186 .def(py::init<float>(),
"sequence_id"_a);
rs2_camera_info
Read-only strings that can be queried from the device. Not all information attributes are available o...
frame allocate_motion_frame(const stream_profile &profile, const frame &original, rs2_extension frame_type=RS2_EXTENSION_MOTION_FRAME) const
void init_processing(py::module &m)
video_frame colorize(frame depth) const
void enqueue(frame f) const
frame wait_for_frame(unsigned int timeout_ms=5000) const
#define BIND_DOWNCAST(class, downcast)
bool supports(rs2_camera_info info) const
void map_to(frame mapped)
frame allocate_points(const stream_profile &profile, const frame &original) const
GLint GLint GLint GLint GLint GLint GLint GLbitfield GLenum filter
void frame_ready(frame result) const
frameset wait_for_frames(unsigned int timeout_ms=5000) const
frame allocate_video_frame(const stream_profile &profile, const frame &original, int new_bpp=0, int new_width=0, int new_height=0, int new_stride=0, rs2_extension frame_type=RS2_EXTENSION_VIDEO_FRAME) const
frameset process(frameset frames)
bool zero_order_invalidation(const uint16_t *depth_data_in, const uint8_t *ir_data, T zero_pixel, const rs2::vertex *vertices, rs2_intrinsics intrinsics, const zero_order_options &options, int zo_point_x, int zo_point_y)
def pointcloud(out, verts, texcoords, color, painter=True)
points calculate(frame depth) const
frame allocate_composite_frame(std::vector< frame > frames) const
const char * get_info(rs2_camera_info info) const
void invoke(frame f) const