9 #include "../include/librealsense2/rs_advanced_mode.hpp" 18 # define SECTION_FROM_TEST_NAME space_to_underscore(Catch::getCurrentContext().getResultCapture()->getCurrentTestName()).c_str() 79 auto processed =
input;
106 std::vector<uint16_t> diff2orig;
107 std::vector<uint16_t> diff2ref;
116 CAPTURE(result_profile.width());
117 CAPTURE(result_profile.height());
122 auto pixels = result_profile.width()*result_profile.height();
123 diff2ref.resize(pixels);
124 if (domain_transform_only)
125 diff2orig.resize(pixels);
138 if (domain_transform_only)
143 return profile_diffs(
"./Filterstransform.txt", diff2ref, 0.
f, 0, frame_idx);
152 REQUIRE(origin_supported == result_supported);
153 if (origin_supported && result_supported)
162 REQUIRE(origin_val == result_val);
173 {
"1551257764229",
"D435_DS(2)"},
174 {
"1551257812956",
"D435_DS(3)"},
176 {
"1551257880762",
"D435_DS(2)_HoleFill(0)" },
177 {
"1551257882796",
"D435_DS(2)_HoleFill(1)" },
178 {
"1551257884097",
"D435_DS(2)_HoleFill(2)" },
180 {
"1551257987255",
"D435_DS(2)+Spat(A:0.85/D:32/I:3)" },
181 {
"1551259481873",
"D435_DS(2)+Spat(A:0.5/D:15/I:2)" },
183 {
"1551261946511",
"D435_DS(2)+Temp(A:0.25/D:15/P:0)" },
184 {
"1551262153516",
"D435_DS(2)+Temp(A:0.45/D:25/P:1)" },
185 {
"1551262256875",
"D435_DS(2)+Temp(A:0.5/D:30/P:4)" },
186 {
"1551262841203",
"D435_DS(2)+Temp(A:0.5/D:30/P:6)" },
187 {
"1551262772964",
"D435_DS(2)+Temp(A:0.5/D:30/P:8)" },
189 {
"1551262971309",
"D435_DS(2)_Spat(A:0.7/D:25/I:2)_Temp(A:0.6/D:15/P:6)" },
191 {
"1551263177558",
"D435_DS(2)_Spat(A:0.7/D:25/I:2)_Temp(A:0.6/D:15/P:6))_HoleFill(1)" },
196 TEST_CASE(
"Post-Processing Filters sequence validation",
"[software-device][post-processing-filters]")
209 WARN(
"PPF test " << ppf_test.first <<
"[" << ppf_test.second <<
"]");
228 width / 2.f, height / 2.f,
254 depth_stream_profile });
262 auto filtered_depth = ppf.
process(depth);
271 TEST_CASE(
"Post-Processing Filters metadata validation",
"[software-device][post-processing-filters]")
283 WARN(
"PPF test " << ppf_test.first <<
"[" << ppf_test.second <<
"]");
302 width / 2.f, height / 2.f,
330 depth_stream_profile });
338 auto filtered_depth = ppf.
process(depth);
351 if (full.
size() == 0 && sub.
size() == 0)
355 if (!sub.
first(
f.get_profile().stream_type(),
f.get_profile().format()))
369 auto curr_profile = o.get_profile();
374 if (curr_profile.unique_id() == processed_profile.unique_id())
383 TEST_CASE(
"Post-Processing expected output",
"[post-processing-filters]")
405 bool supports_disparity =
false;
406 for (
auto s :
profile.get_device().query_sensors())
410 supports_disparity =
true;
443 if(supports_disparity)
487 if (supports_disparity)
502 TEST_CASE(
"Post-Processing processing pipe",
"[post-processing-filters]")
525 bool supports_disparity =
false;
526 for (
auto s :
profile.get_device().query_sensors())
530 supports_disparity =
true;
540 size_t uid_count = 0;
560 uid_count = uids.size();
561 REQUIRE(uid_count == uids.size());
569 TEST_CASE(
"Align Processing Block",
"[live][pipeline][post-processing-filters][!mayfail]") {
595 std::vector<rs2::stream_profile> active_streams;
600 for (
auto i = 0;
i < 300;
i++)
610 std::set<rs2_stream> streams_under_test;
614 if (
auto fr = fs.first_or_default(str_type))
615 streams_under_test.insert(str_type);
619 if (!fs.get_depth_frame() || !streams_under_test.size())
621 WARN(
"Align block test requires a device with Depth and Video sensor(s): current device " 622 <<
"[" << PID.first <<
":" << PID.second <<
"]. Test skipped");
628 WARN(
"Testing Depth aligned to 2D video stream");
629 for (
auto& tgt_stream : streams_under_test)
633 auto aligned_fs = align_pb.
process(fs);
636 auto reference_frame = aligned_fs.first(tgt_stream);
638 auto orig_dpt_profile = origin_depth_frame.get_profile();
646 REQUIRE(orig_dpt_profile == aligned_dpt_profile);
647 REQUIRE(orig_dpt_profile.unique_id() != aligned_dpt_profile.unique_id());
651 REQUIRE(aligned_dpth_video_pf.width() == ref_video_profile.
width());
652 REQUIRE(aligned_dpth_video_pf.height() == ref_video_profile.
height());
654 const auto align_dpt_intr = aligned_dpth_video_pf.get_intrinsics();
655 for (
auto i = 0;
i < 5;
i++)
663 REQUIRE(ref_intr.model == align_dpt_intr.model);
664 REQUIRE(ref_intr.width == align_dpt_intr.width);
665 REQUIRE(ref_intr.height == align_dpt_intr.height);
669 rs2_extrinsics expected_extrinsics = { {1,0,0, 0,1,0, 0,0,1}, {0,0,0} };
672 for (
auto i = 0;
i < 9;
i++)
676 for (
auto i = 0;
i < 3;
i++)
682 WARN(
"Testing 2D Video stream aligned to Depth sensor");
684 for (
auto& tgt_stream : streams_under_test)
688 auto aligned_fs = align_pb.
process(fs);
689 auto origin_2D_frame = fs.
first(tgt_stream);
690 auto aligned_2D_frame = aligned_fs.first(tgt_stream);
693 auto orig_2D_profile = origin_2D_frame.get_profile();
699 REQUIRE(orig_2D_profile == aligned_2D_profile);
700 REQUIRE(orig_2D_profile.unique_id() != aligned_2D_profile.unique_id());
704 REQUIRE(aligned_2D_profile.width() == ref_video_profile.
width());
705 REQUIRE(aligned_2D_profile.height() == ref_video_profile.
height());
707 const auto align_2D_intr = aligned_2D_profile.get_intrinsics();
708 for (
auto i = 0;
i < 5;
i++)
716 REQUIRE(ref_intr.model == align_2D_intr.model);
717 REQUIRE(ref_intr.width == align_2D_intr.width);
718 REQUIRE(ref_intr.height == align_2D_intr.height);
721 rs2_extrinsics actual_extrinsics = aligned_2D_profile.get_extrinsics_to(ref_video_profile);
722 rs2_extrinsics expected_extrinsics = { {1,0,0, 0,1,0, 0,0,1}, {0,0,0} };
725 for (
auto i = 0;
i < 9;
i++)
729 for (
auto i = 0;
i < 3;
i++)
frame apply_filter(filter_interface &filter)
frameset wait_for_frames(unsigned int timeout_ms=RS2_DEFAULT_TIMEOUT) const
rs2::disparity_transform disparity_to_depth
rs2_metadata_type get_frame_metadata(rs2_frame_metadata_value frame_metadata) const
TEST_CASE("Post-Processing Filters sequence validation","[software-device][post-processing-filters]")
rs2_extrinsics get_extrinsics_to(const stream_profile &to) const
stream_profile get_profile() const
device_list query_devices() const
bool load_test_configuration(const std::string test_name, ppf_test_config &test_config)
bool try_wait_for_frames(frameset *f, unsigned int timeout_ms=RS2_DEFAULT_TIMEOUT) const
GLint GLint GLsizei GLsizei GLsizei depth
const void * get_data() const
bool supports_frame_metadata(rs2_frame_metadata_value frame_metadata) const
bool is_equal(rs2::frameset org, rs2::frameset processed)
post_processing_filters(void)
rs2::frame process(rs2::frame input_frame)
std::vector< std::vector< uint8_t > > _output_frames
bool validate_ppf_results(rs2::frame origin_depth, rs2::frame result_depth, const ppf_test_config &reference_data, size_t frame_idx)
frameset wait_for_frames(unsigned int timeout_ms=5000) const
depth_frame get_depth_frame() const
frame first_or_default(rs2_stream s, rs2_format f=RS2_FORMAT_ANY) const
rs2::frame process(rs2::frame frame) const override
frame first(rs2_stream s, rs2_format f=RS2_FORMAT_ANY) const
frameset process(frameset frames)
~post_processing_filters() noexcept
rs2::temporal_filter temp_filter
GLint GLsizei GLsizei height
size_t frames_sequence_size
#define REQUIRE_THROWS(...)
rs2::disparity_transform depth_to_disparity
std::pair< std::string, bool > dev_type
rs2::hole_filling_filter hole_filling_filter
void enable_all_streams()
GLint GLint GLsizei GLint GLenum GLenum const void * pixels
rs2_intrinsics get_intrinsics() const
device get_device() const
const std::vector< std::pair< std::string, std::string > > ppf_test_cases
bool make_context(const char *id, rs2::context *ctx, std::string min_api_version="0.0.0")
rs2::decimation_filter dec_filter
void foreach_rs(T action) const
#define SECTION_FROM_TEST_NAME
Cross-stream extrinsics: encodes the topology describing how the different devices are oriented...
GLdouble GLdouble GLint GLint GLdouble v1
rs2_format format() const
pipeline_profile resolve(std::shared_ptr< rs2_pipeline > p) const
void configure(const ppf_test_config &filters_cfg)
std::vector< stream_profile > get_streams() const
dev_type get_PID(rs2::device &dev)
const char * rs2_stream_to_string(rs2_stream stream)
GLenum GLenum GLenum input
long long rs2_metadata_type
bool profile_diffs(const std::string &plot_name, std::vector< T > &distances, const float max_allowed_std, const float outlier, size_t frame_idx)
#define REQUIRE_FALSE(...)
REQUIRE_NOTHROW(rs2_log(RS2_LOG_SEVERITY_INFO,"Log message using rs2_log()", nullptr))
void disable_sensitive_options_for(rs2::sensor &sen)
bool is_subset(rs2::frameset full, rs2::frameset sub)
void compare_frame_md(rs2::frame origin_depth, rs2::frame result_depth)
uint8_t temporal_persistence
rs2_stream stream_type() const
void set_option(rs2_option option, float value) const
rs2_frame_metadata_value
Per-Frame-Metadata is the set of read-only properties that might be exposed for each individual frame...
rs2::spatial_filter spat_filter
std::vector< std::vector< uint8_t > > _input_frames