5 #ifndef LIBREALSENSE_UNITTESTS_COMMON_H 6 #define LIBREALSENSE_UNITTESTS_COMMON_H 9 #include "../include/librealsense2/rs.hpp" 10 #include "../include/librealsense2/hpp/rs_context.hpp" 11 #include "../include/librealsense2/hpp/rs_internal.hpp" 18 #include <condition_variable> 23 #include "../src/types.h" 33 #define NOEXCEPT_FALSE 35 #define NOEXCEPT_FALSE noexcept(false) 52 format == other.
format() &&
53 width == other.
width() &&
54 height == other.
height() &&
70 return stream == other.
stream &&
71 (format == 0 || other.
format == 0 || format == other.
format) &&
72 (width == 0 || other.
width == 0 || width == other.
width) &&
73 (height == 0 || other.
height == 0 || height == other.
height) &&
74 (index == 0 || other.
index == 0 || index == other.
index);
79 return !(*
this == other);
83 return stream < other.
stream;
103 std::vector<profile> all_profiles =
117 std::vector<rs2::stream_profile> modes;
120 for (
auto profile : all_profiles)
155 }) != all_modes.end())
161 if (modes.size() > 0)
169 std::vector<rs2::sensor> sensors;
174 profiles.insert(profiles.end(),
res.begin(),
res.end());
177 sensors.push_back(
s);
181 return{ sensors, profiles };
188 size_t start_pos = 0;
189 while ((start_pos = temp.find(from, start_pos)) != std::string::npos) {
190 temp.replace(start_pos, from.size(), to);
191 start_pos += to.size();
196 #define SECTION_FROM_TEST_NAME space_to_underscore(Catch::getCurrentContext().getResultCapture()->getCurrentTestName()).c_str() 237 WARN(
"Reset workaround");
240 dev->hardware_reset();
250 bool usb3_device =
true;
255 usb3_device = (std::string::npos ==
usb_type.find(
"2."));
269 dev_type designator{
"",
true };
271 bool usb_descriptor =
false;
278 designator.second = (std::string::npos ==
usb_type.find(
"2."));
289 for (
auto i = 0;
i < argc;
i++)
291 _params.push_back(argv[
i]);
295 char *
const *
get_argv()
const {
return _params.data(); }
305 bool _found_any_section =
false;
313 std::ifstream
f(filename);
321 static std::map<std::string, int> _counters;
332 for (
auto i = 0u;
i < argc;
i++)
340 base_filename = argv[
i];
344 else if (param ==
"from")
349 base_filename = argv[
i];
355 std::stringstream ss;
356 ss <<
id <<
"." << _counters[
id] <<
".test";
391 assert(!std::uncaught_exception());
393 if (validate_error_message)
411 assert(!std::uncaught_exception());
422 return a[0] *
b[0] +
a[1] *
b[1] +
a[2] *
b[2];
462 const float row0[] = {
matrix[0],
matrix[3], matrix[6] };
463 const float row1[] = { matrix[1], matrix[4], matrix[7] };
464 const float row2[] = { matrix[2], matrix[5], matrix[8] };
490 static const float identity_matrix_3x3[] = { 1,0,0, 0,1,0, 0,0,1 };
491 for (
int i = 0;
i < 9; ++
i)
498 std::chrono::high_resolution_clock::time_point
start_time, end_time;
521 frame_number(frame_num),
522 timestamp_domain(ts_domain),
529 REQUIRE(actual_fps >= configured_fps * 0.9);
613 static std::condition_variable
cv;
624 std::lock_guard<std::mutex>
lock(cb_mtx);
633 for (
auto& elem :
data->number_of_frames_per_stream)
635 if (elem.second <
data->duration_per_stream[stream_type].actual_frames_to_receive)
645 stop_streaming =
true;
647 std::lock_guard<std::mutex> lk(m);
654 if (
data->duration_per_stream[stream_type].is_end_time_initialized)
return;
656 unsigned num_of_frames = 0;
657 num_of_frames = (++
data->number_of_frames_per_stream[stream_type]);
659 if (num_of_frames >=
data->duration_per_stream[stream_type].actual_frames_to_receive)
661 if (!
data->duration_per_stream[stream_type].is_end_time_initialized)
664 data->duration_per_stream[stream_type].is_end_time_initialized =
true;
670 if ((num_of_frames ==
data->duration_per_stream[stream_type].first_frame_to_capture) && (!
data->duration_per_stream[stream_type].is_start_time_initialized))
673 data->duration_per_stream[stream_type].is_start_time_initialized =
true;
760 REQUIRE(first_value >= range.min);
761 REQUIRE(first_value <= range.max);
762 CHECK(first_value == range.def);
765 for (
auto value : good_values)
772 float last_good_value;
774 for (
auto value : bad_values)
793 width = video.width();
799 std::stringstream ss;
800 ss <<
"stream profile for " << width <<
"," <<
height <<
" resolution is not supported!";
801 throw std::runtime_error(ss.str());
807 bool disconnected =
false;
808 bool connected =
false;
809 std::shared_ptr<rs2::device>
result;
810 std::condition_variable
cv;
816 std::unique_lock<std::mutex>
lock(m);
823 for (
auto cam : list)
827 std::unique_lock<std::mutex>
lock(m);
829 result = std::make_shared<rs2::device>(cam);
841 std::unique_lock<std::mutex>
lock(m);
843 return cv.wait_for(lock, std::chrono::seconds(20), [&]() {
return disconnected; });
845 REQUIRE(cv.wait_for(lock, std::chrono::seconds(20), [&]() { return connected; }));
856 auto shared_dev = std::make_shared<rs2::device>(devices_list.
front());
859 shared_dev->hardware_reset();
878 #include <KnownFolders.h> 887 if (GetTempPath(MAX_PATH, buf) != 0)
890 wcstombs(str, buf, 1023);
910 PWSTR folder_path =
NULL;
911 HRESULT hr = SHGetKnownFolderPath(folder, KF_FLAG_DEFAULT_PATH,
NULL, &folder_path);
915 wcstombs(str, folder_path, 1023);
916 CoTaskMemFree(folder_path);
924 #if defined __linux__ || defined __APPLE__ 926 #include <sys/types.h> 934 const char* tmp_dir = getenv(
"TMPDIR");
935 res = tmp_dir ? tmp_dir :
"/tmp/";
939 const char* home_dir = getenv(
"HOME");
942 struct passwd* pw = getpwuid(getuid());
943 home_dir = (pw && pw->pw_dir) ? pw->pw_dir :
"";
959 throw std::invalid_argument(
966 #endif // defined __linux__ || defined __APPLE__
static const textual_icon lock
uint32_t first_frame_to_capture
GLboolean GLboolean GLboolean b
require_error(std::string message, bool message_validation=true)
bool operator<(const profile &other) const
std::ostream & operator<<(std::ostream &stream, const profile &cap)
std::string space_to_underscore(const std::string &text)
~require_no_error() NOEXCEPT_FALSE
std::vector< sensor > query_sensors() const
uint32_t frames_to_capture
bool operator!=(const profile &other) const
rs2::stream_profile get_profile_by_resolution_type(rs2::sensor &s, res_type res)
const int max_capture_time_sec
rs2_option
Defines general configuration controls. These can generally be mapped to camera UVC controls...
std::vector< profile > configure_all_supported_streams(rs2::sensor &sensor, int width=640, int height=480, int fps=60)
#define CHECK_THAT(arg, matcher)
#define REQUIRE_THROWS_AS(expr, exceptionType)
stream_profile get_profile() const
bool is_end_time_initialized
std::string get_folder_path(special_folder f)
const void * get_data() const
internal_frame_additional_data(const double &ts, const unsigned long long frame_num, const rs2_timestamp_domain &ts_domain, const rs2_stream &strm, const rs2_format &fmt)
GLsizei const GLchar *const * string
std::map< rs2_stream, unsigned > number_of_frames_per_stream
void require_cross_product(const float(&r)[3], const float(&a)[3], const float(&b)[3])
static const textual_icon stop
void require_zero_vector(const float(&vector)[3])
uint32_t actual_frames_to_receive
const uint32_t max_frames_to_receive
char * get_argv(int i) const
GLboolean GLboolean GLboolean GLboolean a
GLenum GLuint GLenum GLsizei const GLchar * buf
static const textual_icon usb_type
def info(name, value, persistent=False)
std::string full_precision(T const d)
void frame_callback(rs2::device &dev, rs2::frame frame, void *user)
const char * rs2_get_error_message(const rs2_error *error)
char *const * get_argv() const
double get_timestamp() const
bool validate_error_message
const char * get_info(rs2_camera_info info) const
void require_rotation_matrix(const float(&matrix)[9])
GLint GLsizei GLsizei height
static std::condition_variable cv
void require_transposed(const float(&a)[9], const float(&b)[9])
bool wait_for_reset(std::function< bool(void)> func, std::shared_ptr< rs2::device > dev)
float vector_length(const float(&v)[3])
rs2::depth_sensor restart_first_device_and_return_depth_sensor(const rs2::context &ctx, const rs2::device_list &devices_list)
rs2_format
A stream's format identifies how binary data is encoded within a frame.
GLenum const GLfloat * params
std::pair< std::string, bool > dev_type
void log_to_file(rs2_log_severity min_severity, const char *file_path=nullptr)
bool supports(rs2_camera_info info) const
rs2_stream
Streams are different types of data provided by RealSense devices.
std::vector< profile > streams
bool supports(rs2_camera_info info) const
bool is_start_time_initialized
bool make_context(const char *id, rs2::context *ctx, std::string min_api_version="0.0.0")
float dot_product(const float(&a)[3], const float(&b)[3])
void require_identity_matrix(const float(&matrix)[9])
std::map< rs2_stream, test_duration > duration_per_stream
~require_error() NOEXCEPT_FALSE
rs2_format format() const
rs2_timestamp_domain timestamp_domain
bool operator==(const rs2::video_stream_profile &other) const
void check_fps(double actual_fps, double configured_fps)
dev_type get_PID(rs2::device &dev)
void test_option(rs2::sensor &device, rs2_option option, std::initializer_list< int > good_values, std::initializer_list< int > bad_values)
static std::atomic< bool > stop_streaming
typename::boost::move_detail::remove_reference< T >::type && move(T &&t) BOOST_NOEXCEPT
void open(const stream_profile &profile) const
void set_devices_changed_callback(T callback)
static command_line_params & instance(int argc=0, char *const argv[]=0)
std::shared_ptr< rs2::device > do_with_waiting_for_camera_connection(rs2::context ctx, std::shared_ptr< rs2::device > dev, std::string serial, std::function< void()> operation)
REQUIRE_NOTHROW(rs2_log(RS2_LOG_SEVERITY_INFO,"Log message using rs2_log()", nullptr))
void disable_sensitive_options_for(rs2::sensor &sen)
option_range get_option_range(rs2_option option) const
std::vector< char * > _params
bool file_exists(const std::string &filename)
unsigned long long frame_number
bool is_usb3(const rs2::device &dev)
std::vector< stream_profile > get_stream_profiles() const
bool operator==(const profile &other) const
rs2_stream stream_type() const
void set_option(rs2_option option, float value) const
float get_option(rs2_option option) const
command_line_params(int argc, char *const argv[])
res_type get_res_type(uint32_t width, uint32_t height)
std::chrono::high_resolution_clock::time_point start_time
std::string to_string(T value)
rs2_timestamp_domain
Specifies the clock in relation to which the frame timestamp was measured.