4 #ifndef LIBREALSENSE_RS2_PROCESSING_HPP 5 #define LIBREALSENSE_RS2_PROCESSING_HPP 34 const frame& original,
43 original.
get(), new_bpp, new_width, new_height, new_stride, frame_type, &
e);
57 const frame& original,
62 original.
get(), frame_type, &
e);
68 const frame& original)
const 86 std::vector<rs2_frame*> refs(frames.size(), (
rs2_frame*)
nullptr);
87 for (
size_t i = 0;
i < frames.size();
i++)
143 explicit frame_queue(
unsigned int capacity,
bool keep_frames =
false) : _capacity(capacity), _keep(keep_frames)
146 _queue = std::shared_ptr<rs2_frame_queue>(
190 if (
res) *output =
f;
202 if (
res) *output =
f;
295 _block = std::shared_ptr<rs2_processing_block>(
315 return is_supported > 0;
337 std::shared_ptr<rs2_processing_block>
_block;
356 if (!_queue.poll_for_frame(&f))
357 throw std::runtime_error(
"Error occured during execution of the processing block! See the log for more info");
366 filter(std::shared_ptr<rs2_processing_block> block,
int queue_size = 1)
379 filter(S processing_function,
int queue_size = 1) :
404 operator bool()
const {
return _block.get() !=
nullptr; }
433 auto res = process(depth);
445 throw std::runtime_error(
"Error occured during execution of the processing block! See the log for more info");
466 std::shared_ptr<rs2_processing_block>
init()
470 auto block = std::shared_ptr<rs2_processing_block>(
499 std::shared_ptr<rs2_processing_block>
init()
502 auto block = std::shared_ptr<rs2_processing_block>(
540 std::shared_ptr<rs2_processing_block>
init()
543 auto block = std::shared_ptr<rs2_processing_block>(
564 std::shared_ptr<rs2_processing_block>
init()
567 auto block = std::shared_ptr<rs2_processing_block>(
585 std::shared_ptr<rs2_processing_block>
init()
588 auto block = std::shared_ptr<rs2_processing_block>(
604 :_results(queue_size)
606 _sync.start(_results);
616 return frameset(_results.wait_for_frame(timeout_ms));
627 if (_results.poll_for_frame(&result))
644 if (_results.try_wait_for_frame(&result, timeout_ms))
692 align(std::shared_ptr<rs2_processing_block> block) :
filter(block, 1) {}
699 auto block = std::shared_ptr<rs2_processing_block>(
742 return process(depth);
749 std::shared_ptr<rs2_processing_block>
init()
752 auto block = std::shared_ptr<rs2_processing_block>(
795 std::shared_ptr<rs2_processing_block>
init()
798 auto block = std::shared_ptr<rs2_processing_block>(
856 std::shared_ptr<rs2_processing_block>
init()
859 auto block = std::shared_ptr<rs2_processing_block>(
912 std::shared_ptr<rs2_processing_block>
init()
915 auto block = std::shared_ptr<rs2_processing_block>(
947 std::shared_ptr<rs2_processing_block>
init(
bool transform_to_disparity)
950 auto block = std::shared_ptr<rs2_processing_block>(
985 std::shared_ptr<rs2_processing_block>
init()
988 auto block = std::shared_ptr<rs2_processing_block>(
1019 std::shared_ptr<rs2_processing_block>
init()
1022 auto block = std::shared_ptr<rs2_processing_block>(
1065 std::shared_ptr<rs2_processing_block>
init()
1068 auto block = std::shared_ptr<rs2_processing_block>(
1092 std::shared_ptr<rs2_processing_block>
init()
1095 auto block = std::shared_ptr<rs2_processing_block>(
1127 std::shared_ptr<rs2_processing_block>
init()
1130 auto block = std::shared_ptr<rs2_processing_block>(
1171 std::shared_ptr<rs2_processing_block>
init()
1174 auto block = std::shared_ptr<rs2_processing_block>(
1183 #endif // LIBREALSENSE_RS2_PROCESSING_HPP std::shared_ptr< rs2_processing_block > init()
rs2_processing_block * rs2_create_decimation_filter_block(rs2_error **error)
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
threshold_filter(std::shared_ptr< rs2_processing_block > block)
rs2_processing_block * rs2_create_threshold(rs2_error **error)
bool try_wait_for_frames(frameset *fs, unsigned int timeout_ms=5000) const
std::shared_ptr< rs2_processing_block > _block
rs2_frame * rs2_allocate_composite_frame(rs2_source *source, rs2_frame **frames, int count, rs2_error **error)
hole_filling_filter(filter f)
threshold_filter(filter f)
asynchronous_syncer _sync
rs2_option
Defines general configuration controls. These can generally be mapped to camera UVC controls...
rs2_processing_block * rs2_create_zero_order_invalidation_block(rs2_error **error)
rs2_frame * rs2_allocate_points(rs2_source *source, const rs2_stream_profile *new_stream, rs2_frame *original, rs2_error **error)
rs2_processing_block * rs2_create_units_transform(rs2_error **error)
void rs2_start_processing(rs2_processing_block *block, rs2_frame_callback *on_frame, rs2_error **error)
std::shared_ptr< rs2_processing_block > init()
int rs2_poll_for_frame(rs2_frame_queue *queue, rs2_frame **output_frame, rs2_error **error)
std::shared_ptr< rs2_processing_block > init()
align(std::shared_ptr< rs2_processing_block > block)
void on_frame(rs2_frame *f, rs2_source *source) override
rs2_processing_block * rs2_create_hole_filling_filter_block(rs2_error **error)
std::enable_if< std::is_base_of< rs2::frame, T >::value, bool >::type poll_for_frame(T *output) const
rs2_processing_block * rs2_create_sync_processing_block(rs2_error **error)
video_frame colorize(frame depth) const
stream_profile get_profile() const
void enqueue(frame f) const
void register_simple_option(rs2_option option_id, option_range range)
void operator()(frame f) const
std::shared_ptr< rs2_processing_block > init()
frame wait_for_frame(unsigned int timeout_ms=5000) const
std::function< void(frame_interface *)> on_frame
pointcloud(rs2_stream stream, int index=0)
rs2_processing_block * rs2_create_processing_block(rs2_frame_processor_callback *proc, rs2_error **error)
GLint GLint GLsizei GLsizei GLsizei depth
void rs2_delete_frame_queue(rs2_frame_queue *queue)
bool supports(rs2_camera_info info) const
void map_to(frame mapped)
frame allocate_points(const stream_profile &profile, const frame &original) const
rs2_frame_queue * rs2_create_frame_queue(int capacity, rs2_error **error)
rs2_frame * rs2_wait_for_frame(rs2_frame_queue *queue, unsigned int timeout_ms, rs2_error **error)
void rs2_process_frame(rs2_processing_block *block, rs2_frame *frame, rs2_error **error)
colorizer(float color_scheme)
rs2_processing_block * rs2_create_huffman_depth_decompress_block(rs2_error **error)
std::shared_ptr< rs2_processing_block > init()
int rs2_processing_block_register_simple_option(rs2_processing_block *block, rs2_option option_id, float min, float max, float step, float def, rs2_error **error)
void frame_ready(frame result) const
processing_block(std::shared_ptr< rs2_processing_block > block)
threshold_filter(float min_dist=0.15f, float max_dist=4.f)
frameset wait_for_frames(unsigned int timeout_ms=5000) const
std::shared_ptr< rs2_processing_block > init()
rs2_processing_block * rs2_create_rates_printer_block(rs2_error **error)
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
def info(name, value, persistent=False)
align(rs2_stream align_to)
rs2_frame * rs2_allocate_synthetic_video_frame(rs2_source *source, const rs2_stream_profile *new_stream, rs2_frame *original, int new_bpp, int new_width, int new_height, int new_stride, rs2_extension frame_type, rs2_error **error)
rs2_processing_block * rs2_create_align(rs2_stream align_to, rs2_error **error)
rs2::frame process(rs2::frame frame) const override
depth_huffman_decoder(filter f)
std::shared_ptr< rs2_processing_block > init()
rs2_processing_block * rs2_create_pointcloud(rs2_error **error)
temporal_filter(float smooth_alpha, float smooth_delta, int persistence_control)
void rs2_enqueue_frame(rs2_frame *frame, void *queue)
frameset process(frameset frames)
std::shared_ptr< rs2_processing_block > init()
zero_order_invalidation(filter f)
processing_block(S processing_function)
int rs2_supports_processing_block_info(const rs2_processing_block *block, rs2_camera_info info, rs2_error **error)
decimation_filter(float magnitude)
points calculate(frame depth) const
void rs2_synthetic_frame_ready(rs2_source *source, rs2_frame *frame, rs2_error **error)
frame allocate_composite_frame(std::vector< frame > frames) const
std::enable_if< std::is_base_of< rs2::frame, T >::value, bool >::type try_wait_for_frame(T *output, unsigned int timeout_ms=5000) const
sequence_id_filter(filter f)
decimation_filter(filter f)
S & operator>>(S &on_frame)
frame_source(rs2_source *source)
BOOST_DEDUCED_TYPENAME optional< T >::reference_const_type get(optional< T > const &opt)
void rs2_delete_processing_block(rs2_processing_block *block)
filter(S processing_function, int queue_size=1)
rs2_processing_block * rs2_create_temporal_filter_block(rs2_error **error)
std::shared_ptr< rs2_processing_block > init()
void operator()(frame f) const
bool supports(rs2_option option) const
void swap(nlohmann::json &j1, nlohmann::json &j2) noexcept(is_nothrow_move_constructible< nlohmann::json >::value andis_nothrow_move_assignable< nlohmann::json >::value)
exchanges the values of two JSON objects
static void handle(rs2_error *e)
rs2_processing_block * rs2_create_disparity_transform_block(unsigned char transform_to_disparity, rs2_error **error)
rs2_processing_block * rs2_create_colorizer(rs2_error **error)
rs2_stream
Streams are different types of data provided by RealSense devices.
bool poll_for_frames(frameset *fs) const
std::shared_ptr< rs2_processing_block > init()
std::shared_ptr< rs2_processing_block > init(rs2_stream align_to)
rs2_processing_block * rs2_create_sequence_id_filter(rs2_error **error)
zero_order_invalidation()
std::shared_ptr< rs2_processing_block > init()
rs2_format format() const
yuy_decoder(std::shared_ptr< rs2_processing_block > block)
filter(std::shared_ptr< rs2_processing_block > block, int queue_size=1)
rs2_frame * rs2_allocate_synthetic_motion_frame(rs2_source *source, const rs2_stream_profile *new_stream, rs2_frame *original, rs2_extension frame_type, rs2_error **error)
std::shared_ptr< rs2_processing_block > init()
rs2_processing_block * rs2_create_yuy_decoder(rs2_error **error)
rs2_extension
Specifies advanced interfaces (capabilities) objects may implement.
const char * get_info(rs2_camera_info info) const
const rs2_stream_profile * get() const
sequence_id_filter(float sequence_id)
void invoke(frame f) const
std::shared_ptr< rs2_processing_block > init()
spatial_filter(float smooth_alpha, float smooth_delta, float magnitude, float hole_fill)
rs2_processing_block * rs2_create_spatial_filter_block(rs2_error **error)
frame_processor_callback(T on_frame)
typename::boost::move_detail::remove_reference< T >::type && move(T &&t) BOOST_NOEXCEPT
options & operator=(const options &other)
GLsizei GLsizei GLchar * source
rs2_processing_block * get() const
frame_queue(unsigned int capacity, bool keep_frames=false)
int rs2_try_wait_for_frame(rs2_frame_queue *queue, unsigned int timeout_ms, rs2_frame **output_frame, rs2_error **error)
int rs2_is_processing_block_extendable_to(const rs2_processing_block *block, rs2_extension extension_type, rs2_error **error)
hole_filling_filter(int mode)
const char * rs2_get_processing_block_info(const rs2_processing_block *block, rs2_camera_info info, rs2_error **error)
rs2_stream stream_type() const
std::shared_ptr< rs2_processing_block > init()
std::shared_ptr< rs2_frame_queue > _queue
colorizer(std::shared_ptr< rs2_processing_block > block)
pointcloud(std::shared_ptr< rs2_processing_block > block)
rs2_processing_block * rs2_create_hdr_merge_processing_block(rs2_error **error)
struct rs2_frame rs2_frame
temporal_filter(filter f)