unit-test-long.cpp
Go to the documentation of this file.
1 #include <cmath>
2 #include "unit-tests-common.h"
5 #include <iostream>
6 #include <chrono>
7 #include <ctime>
8 #include <algorithm>
9 #include <librealsense2/rsutil.h>
10 
11 using namespace rs2;
12 using namespace std::chrono;
13 
14 #ifdef __linux__
15 #include <sys/wait.h>
16 #include <semaphore.h>
17 #include <fcntl.h>
18 
19 bool stream(std::string serial_number, sem_t* sem2, bool do_query)
20 {
21  signal(SIGTERM, [](int signum) { std::cout << "SIGTERM: " << getpid() << std::endl; exit(1);});
22 
24  if (do_query)
25  {
26  rs2::device_list list(ctx.query_devices());
27  bool found_sn(false);
28  for (auto&& dev : ctx.query_devices())
29  {
30  if (dev.get_info(RS2_CAMERA_INFO_SERIAL_NUMBER) == serial_number)
31  {
32  found_sn = true;
33  }
34  }
35  REQUIRE(found_sn);
36  }
37  rs2::pipeline pipe(ctx);
39  cfg.enable_device(serial_number);
40  std::cout << "pipe starting: " << serial_number << std::endl;
41  cfg.disable_all_streams();
43  pipe.start(cfg);
44  std::cout << "pipe started: " << serial_number << std::endl;
45 
46  double max_milli_between_frames(3000);
47  double last_frame_time = duration<double, std::milli>(system_clock::now().time_since_epoch()).count();
48  double crnt_time = duration<double, std::milli>(system_clock::now().time_since_epoch()).count();
49  bool is_running(true);
50  int sem_value;
51  while (is_running && crnt_time-last_frame_time < max_milli_between_frames)
52  {
53  rs2::frameset fs;
54  if (pipe.poll_for_frames(&fs))
55  {
56  last_frame_time = duration<double, std::milli>(system_clock::now().time_since_epoch()).count();
57  }
58  crnt_time = duration<double, std::milli>(system_clock::now().time_since_epoch()).count();
59  sem_getvalue(sem2, &sem_value);
60  is_running = (sem_value == 0);
61  }
62  pipe.stop();
63  return true; // TBD
64 }
65 
66 void multiple_stream(std::string serial_number, sem_t* sem, bool do_query)
67 {
68  size_t max_iterations(10);
69  pid_t pid;
70  std::stringstream sem_name;
71  sem_name << "sem_" << serial_number << "_" << 0;
72  bool is_running(true);
73  int sem_value;
74  for (size_t counter=0; counter<10 && is_running; counter++)
75  {
76  sem_unlink(sem_name.str().c_str());
77  sem_t *sem2 = sem_open(sem_name.str().c_str(), O_CREAT|O_EXCL, S_IRWXU, 0);
78  CHECK_FALSE(sem2 == SEM_FAILED);
79  pid = fork();
80  if (pid == 0) // child process
81  {
82  std::cout << "Start streaming: " << serial_number << " : (" << counter+1 << "/" << max_iterations << ")" << std::endl;
83  stream(serial_number, sem2, do_query); //on normal behavior - should block
84  break;
85  }
86  else
87  {
88  std::this_thread::sleep_for(std::chrono::seconds(5));
89  int status;
90  pid_t w = waitpid(pid, &status, WNOHANG);
91  bool child_alive(w == 0);
92  if (child_alive) {
93  sem_post(sem2);
94 
95  // Give 2 seconds to quit before kill:
96  double start_time = duration<double, std::milli>(system_clock::now().time_since_epoch()).count();
97  double crnt_time = duration<double, std::milli>(system_clock::now().time_since_epoch()).count();
98  while (child_alive && (crnt_time - start_time < 2000))
99  {
100  std::this_thread::sleep_for(std::chrono::milliseconds(500));
101  pid_t w = waitpid(pid, &status, WNOHANG);
102  child_alive = (w == 0);
103  crnt_time = duration<double, std::milli>(system_clock::now().time_since_epoch()).count();
104  }
105  if (child_alive)
106  {
107  std::cout << "Failed to start streaming: " << serial_number << std::endl;
108  int res = kill(pid,SIGTERM);
109  pid_t w = waitpid(pid, &status, 0);
110  exit(2);
111  }
112  std::this_thread::sleep_for(std::chrono::milliseconds(100));
113  }
114  else
115  {
116  std::cout << "Frames did not arrive: " << serial_number << std::endl;
117  exit(1);
118  }
119  }
120  sem_getvalue(sem, &sem_value);
121  is_running = (sem_value == 0);
122  }
123  if (pid != 0)
124  {
125  sem_unlink(sem_name.str().c_str());
126  }
127  exit(0);
128 }
129 
130 TEST_CASE("multicam_streaming", "[live][multicam]")
131 {
132  // Test will start and stop streaming on 2 devices simultaneously for 10 times, thus testing the named_mutex mechnism.
135  {
136  std::vector<std::string> serials_numbers;
137  for (auto&& dev : ctx.query_devices())
138  {
141  if ( usb_type != "3.2")
142  {
143  WARN("Device " << serial << " with usb_type " << usb_type << " is skipped.");
144  continue;
145  }
146  serials_numbers.push_back(serial);
147  }
148  REQUIRE(serials_numbers.size() >= 2);
149  std::vector<pid_t> pids;
150  pid_t pid;
151 
152  bool do_query(true);
153  std::vector<sem_t*> sems;
154  for (size_t idx = 0; idx < serials_numbers.size(); idx++)
155  {
156  std::stringstream sem_name;
157  sem_name << "sem_" << idx;
158  sem_unlink(sem_name.str().c_str());
159  sems.push_back(sem_open(sem_name.str().c_str(), O_CREAT|O_EXCL, S_IRWXU, 0));
160  CHECK_FALSE(sems[idx] == SEM_FAILED);
161  pid = fork();
162  if (pid == 0) // child
163  {
164  multiple_stream(serials_numbers[idx], sems[idx], do_query); //on normal behavior - should block
165  }
166  else
167  {
168  std::this_thread::sleep_for(std::chrono::milliseconds(100));
169  pids.push_back(pid);
170  }
171  }
172  if (pid != 0)
173  {
174  int status0;
175  pid_t pid = wait(&status0);
176  std::cout << "status0 = " << status0 << std::endl;
177  for (auto sem : sems)
178  {
179  sem_post(sem);
180  }
181  for (auto pid : pids)
182  {
183  int status;
184  pid_t w = waitpid(pid, &status, WNOHANG);
185  std::cout << "status: " << pid << " : " << status << std::endl;
186  bool child_alive(w == 0);
187 
188  double start_time = duration<double, std::milli>(system_clock::now().time_since_epoch()).count();
189  double crnt_time = duration<double, std::milli>(system_clock::now().time_since_epoch()).count();
190  while (child_alive && (crnt_time - start_time < 6000))
191  {
192  std::cout << "waiting for: " << pid << std::endl;
193  std::this_thread::sleep_for(std::chrono::milliseconds(500));
194  pid_t w = waitpid(pid, &status, WNOHANG);
195  child_alive = (w == 0);
196  crnt_time = duration<double, std::milli>(system_clock::now().time_since_epoch()).count();
197  }
198  if (child_alive)
199  {
200  std::cout << "kill: " << pid << std::endl;
201  int res = kill(pid,SIGTERM);
202  pid_t w = waitpid(pid, &status, 0);
203  std::cout << "status: " << status << ", " << w << std::endl;
204  }
205  }
206  REQUIRE(status0 == 0);
207  }
208  }
209 }
210 #endif // __linux__
211 
213 {
214  double system_time;
215 
216  global_time_test_meta_data(const double &ts, const unsigned long long frame_num, const rs2_timestamp_domain& ts_domain, const rs2_stream& strm, const rs2_format& fmt, double& sts) :
217  internal_frame_additional_data(ts, frame_num, ts_domain, strm, fmt)
218  {
219  system_time = sts;
220  }
221 };
222 
224 {
225  double min_diff, max_diff;
226 };
227 
228 void run_sensor(rs2::sensor subdevice, rs2::stream_profile profile, bool enable_gts, int iter, double& max_diff_system_global_time)
229 {
230  const double msec_to_sec = 0.001;
231  const int frames_for_fps_measure(profile.fps() * 1); // max number of frames
232 
233  std::vector<global_time_test_meta_data> frames_additional_data;
234  double start_time;
235  std::condition_variable cv;
236  std::mutex m;
237  auto first = true;
238 
239  REQUIRE_NOTHROW(subdevice.open({ profile }));
240 
242  if (enable_gts)
244 
245  REQUIRE_NOTHROW(subdevice.start([&](rs2::frame f)
246  {
247  double crnt_time(internal::get_time());
248  if (first)
249  {
250  start_time = crnt_time;
251  }
252  first = false;
253 
254  if ((frames_additional_data.size() >= frames_for_fps_measure))
255  {
256  cv.notify_one();
257  }
258 
259  if (frames_additional_data.size() < frames_for_fps_measure)
260  {
262  f.get_frame_number(),
264  f.get_profile().stream_type(),
265  f.get_profile().format(),
266  crnt_time
267  };
268 
269  std::unique_lock<std::mutex> lock(m);
270  frames_additional_data.push_back(data);
271  }
272  }));
273 
274  CAPTURE(frames_for_fps_measure);
275 
276  std::unique_lock<std::mutex> lock(m);
277  cv.wait_for(lock, std::chrono::seconds(10), [&] {return ((frames_additional_data.size() >= frames_for_fps_measure)); });
278  CAPTURE(frames_additional_data.size());
279 
280  auto end = internal::get_time();
281  REQUIRE_NOTHROW(subdevice.stop());
282  REQUIRE_NOTHROW(subdevice.close());
283 
284  lock.unlock();
285 
286  auto seconds = (end - start_time)*msec_to_sec;
287 
288  CAPTURE(start_time);
289  CAPTURE(end);
290  CAPTURE(seconds);
291 
292  REQUIRE(seconds > 0);
293 
294  if (frames_additional_data.size())
295  {
296  std::stringstream name;
297  name << "test_results_" << iter << "_" << enable_gts << ".txt";
298  std::ofstream fout(name.str());
299  //std::ofstream fout("test_results.txt");
300  for (auto data : frames_additional_data)
301  {
302  fout << std::fixed << std::setprecision(4) << data.system_time << " " << data.timestamp << " " << rs2_timestamp_domain_to_string(data.timestamp_domain) << std::endl;
303  }
304  fout.close();
305 
306  rs2_timestamp_domain first_timestamp_domain(frames_additional_data[0].timestamp_domain);
307  auto actual_fps = (double)frames_additional_data.size() / (double)seconds;
309  max_diff_system_global_time = 0;
310  for (int i = 1; i < frames_additional_data.size(); i++)
311  {
312  const global_time_test_meta_data& crnt_data = frames_additional_data[i];
313  const global_time_test_meta_data& prev_data = frames_additional_data[i - 1];
314  if ((crnt_data.timestamp_domain != first_timestamp_domain) ||
315  (prev_data.timestamp_domain != first_timestamp_domain))
316  {
317  continue;
318  }
319  double system_ts_diff = crnt_data.system_time - prev_data.system_time;
320  double ts_diff = crnt_data.timestamp - prev_data.timestamp;
321  REQUIRE(system_ts_diff > 0);
322  REQUIRE(ts_diff > 0);
323  double crnt_diff(system_ts_diff - ts_diff); //big positive difference means system load. big negative means big global time correction.
324  max_diff_system_global_time = std::max(max_diff_system_global_time, crnt_diff);
325  }
326  }
327 }
328 
329 TEST_CASE("global-time-start", "[live]") {
330  //Require at least one device to be plugged in
331  // This test checks if there are delays caused by GlobalTimeStampReader:
332  // The test finds the maximal system time difference and frame time difference between every 2 consecutive frames.
333  // It then checks that the maximal difference found between system time and frame time is about the same
334  // for runs with global time stamp on and runs with global time stamp off.
335 
338  {
339  std::vector<sensor> list;
340  REQUIRE_NOTHROW(list = ctx.query_all_sensors());
341  REQUIRE(list.size() > 0);
342 
343  const int frames_before_start_measure = 10;
344  const double msec_to_sec = 0.001;
345  const int num_of_profiles_for_each_subdevice = 2;
346  const float max_diff_between_real_and_metadata_fps = 1.0f;
347 
348  // Find profile with greatest fps:
349  int max_fps(0);
350  for (auto && subdevice : list) {
351  if (!subdevice.supports(RS2_OPTION_GLOBAL_TIME_ENABLED))
352  continue;
353  std::vector<rs2::stream_profile> modes;
354  REQUIRE_NOTHROW(modes = subdevice.get_stream_profiles());
355  REQUIRE(modes.size() > 0);
356  for (auto profile : modes)
357  {
358  if (max_fps < profile.fps())
359  {
360  max_fps = profile.fps();
361  }
362  }
363  }
364 
365  for (auto && subdevice : list) {
366  if (!subdevice.supports(RS2_OPTION_GLOBAL_TIME_ENABLED))
367  continue;
368  std::vector<rs2::stream_profile> modes;
369  REQUIRE_NOTHROW(modes = subdevice.get_stream_profiles());
370 
371  REQUIRE(modes.size() > 0);
372  CAPTURE(subdevice.get_info(RS2_CAMERA_INFO_NAME));
373 
374  //the test will be done only on the profile with maximal fps:
375  for (auto profile : modes)
376  {
377  if (profile.fps() < max_fps)
378  continue;
379 
381  CAPTURE(profile.fps());
382  CAPTURE(profile.stream_type());
383  CAPTURE(profile.stream_index());
384  if (auto video = profile.as<video_stream_profile>())
385  {
386  CAPTURE(video.width());
387  CAPTURE(video.height());
388  }
389 
390  double max_diff_system_global_time;
391  std::vector<double> all_results_gts_on;
392  std::vector<double> all_results_gts_off;
393  const int num_of_runs(30);
394  for (int i = 0; i < num_of_runs; i++)
395  {
396  run_sensor(subdevice, profile, true, i, max_diff_system_global_time);
397  all_results_gts_on.push_back(max_diff_system_global_time);
398  std::cout << "Ran iteration " << i << "/" << num_of_runs << " - gts-ON: max_diff_system_global_time=" << max_diff_system_global_time << std::endl;
399 
400  run_sensor(subdevice, profile, false, i, max_diff_system_global_time);
401  all_results_gts_off.push_back(max_diff_system_global_time);
402  std::cout << "Ran iteration " << i << "/" << num_of_runs << " - gts-OFF: max_diff_system_global_time=" << max_diff_system_global_time << std::endl;
403  }
404  std::nth_element(all_results_gts_on.begin(), all_results_gts_on.begin() + all_results_gts_on.size() / 2, all_results_gts_on.end());
405  double median_diff_gts_on = all_results_gts_on[all_results_gts_on.size() / 2];
406  std::nth_element(all_results_gts_off.begin(), all_results_gts_off.begin() + all_results_gts_off.size() / 2, all_results_gts_off.end());
407  double median_diff_gts_off = all_results_gts_off[all_results_gts_off.size() / 2];
408  CAPTURE(median_diff_gts_on);
409  CAPTURE(median_diff_gts_off);
410 
411  REQUIRE(median_diff_gts_on > 0.5*median_diff_gts_off);
412  REQUIRE(median_diff_gts_on < 2.0*median_diff_gts_off);
413 
414  break; // Check 1 profile only.
415  }
416  }
417  }
418 }
419 
420 std::shared_ptr<std::map<rs2_stream, int>> count_streams_frames(const context& ctx, const sensor& sub, int num_of_frames)
421 {
422  std::shared_ptr<std::condition_variable> cv = std::make_shared<std::condition_variable>();
423  std::shared_ptr<std::mutex> m = std::make_shared<std::mutex>();
424  std::shared_ptr<std::map<rs2_stream, int>> streams_frames = std::make_shared<std::map<rs2_stream, int>>();
425 
426  std::shared_ptr<std::function<void(rs2::frame fref)>> func;
427 
428  std::vector<rs2::stream_profile> modes;
429  REQUIRE_NOTHROW(modes = sub.get_stream_profiles());
430 
431  auto streaming = false;
432 
433  for (auto p : modes)
434  {
435  if (auto video = p.as<video_stream_profile>())
436  {
437  {
438  if ((video.stream_type() == RS2_STREAM_DEPTH && video.format() == RS2_FORMAT_Z16))
439  {
440  streaming = true;
441 
442  REQUIRE_NOTHROW(sub.open(p));
443 
444  func = std::make_shared< std::function<void(frame fref)>>([m, streams_frames, cv](frame fref) mutable
445  {
446  std::unique_lock<std::mutex> lock(*m);
447  auto stream = fref.get_profile().stream_type();
448  if (streams_frames->find(stream) == streams_frames->end())
449  (*streams_frames)[stream] = 0;
450  else
451  (*streams_frames)[stream]++;
452 
453  cv->notify_one();
454  });
455  REQUIRE_NOTHROW(sub.start(*func));
456  break;
457  }
458  }
459  }
460  }
461  REQUIRE(streaming);
462 
463 
464  std::unique_lock<std::mutex> lock(*m);
465  cv->wait_for(lock, std::chrono::seconds(30), [&]
466  {
467  for (auto f : (*streams_frames))
468  {
469  if (f.second > num_of_frames)
470  {
471  return true;
472  }
473  }
474  return false;
475  });
476 
477  lock.unlock();
478  if (streaming)
479  {
480  REQUIRE_NOTHROW(sub.stop());
481  REQUIRE_NOTHROW(sub.close());
482 
483  }
484 
485  return streams_frames;
486 }
487 
488 TEST_CASE("test-depth-only", "[live]") {
489  //Require at least one device to be plugged in
490  // This test checks if once depth is the only profile we ask, it's the only type of frames we get.
491 
494  {
495  std::vector<rs2::device> list;
496  REQUIRE_NOTHROW(list = ctx.query_devices());
497  REQUIRE(list.size() > 0);
498 
499  auto dev = std::make_shared<device>(list.front());
500  auto sensors = dev->query_sensors();
501 
502  sensor d_sensor;
503  for (sensor& elem : sensors)
504  {
505  if (elem.is<depth_sensor>())
506  {
507  d_sensor = elem;
508  break;
509  }
510  }
511  REQUIRE(d_sensor);
512 
513  std::shared_ptr<std::map<rs2_stream, int>> streams_frames = count_streams_frames(ctx, d_sensor, 10);
514  std::cout << "streams_frames.size: " << streams_frames->size() << std::endl;
515  for (auto stream_num : (*streams_frames))
516  {
517  std::cout << "For stream " << stream_num.first << " got " << stream_num.second << " frames." << std::endl;
518  }
519  REQUIRE(streams_frames->find(RS2_STREAM_DEPTH) != streams_frames->end());
520  REQUIRE(streams_frames->size() == 1);
521  }
522 }
static const textual_icon lock
Definition: model-views.h:218
GLuint GLuint end
TEST_CASE("global-time-start","[live]")
GLuint const GLchar * name
std::vector< sensor > query_all_sensors() const
Generate a flat list of all available sensors from all RealSense devices.
Definition: rs_context.hpp:142
const char * rs2_timestamp_domain_to_string(rs2_timestamp_domain info)
Definition: rs.cpp:1267
GLfloat GLfloat p
Definition: glext.h:12687
const GLfloat * m
Definition: glext.h:6814
std::shared_ptr< std::map< rs2_stream, int > > count_streams_frames(const context &ctx, const sensor &sub, int num_of_frames)
stream_profile get_profile() const
Definition: rs_frame.hpp:557
device_list query_devices() const
Definition: rs_context.hpp:112
global_time_test_meta_data(const double &ts, const unsigned long long frame_num, const rs2_timestamp_domain &ts_domain, const rs2_stream &strm, const rs2_format &fmt, double &sts)
Definition: cah-model.h:10
GLdouble GLdouble GLdouble w
GLsizei const GLchar *const * string
void enable_device(const std::string &serial)
GLuint GLuint stream
Definition: glext.h:1790
status
Defines return codes that SDK interfaces use. Negative values indicate errors, a zero value indicates...
static const textual_icon usb_type
Definition: model-views.h:249
GLdouble f
std::ostream & cout()
GLuint counter
Definition: glext.h:5684
#define WARN(msg)
Definition: catch.hpp:17431
#define CAPTURE(...)
Definition: catch.hpp:17432
REQUIRE(n_callbacks==1)
void disable_all_streams()
double get_timestamp() const
Definition: rs_frame.hpp:474
static std::condition_variable cv
#define SECTION_FROM_TEST_NAME
rs2_format
A stream&#39;s format identifies how binary data is encoded within a frame.
Definition: rs_sensor.h:59
GLint first
void enable_stream(rs2_stream stream_type, int stream_index, int width, int height, rs2_format format=RS2_FORMAT_ANY, int framerate=0)
GLenum func
rs2_stream
Streams are different types of data provided by RealSense devices.
Definition: rs_sensor.h:42
static const textual_icon exit
Definition: model-views.h:254
bool make_context(const char *id, rs2::context *ctx, std::string min_api_version="0.0.0")
void run_sensor(rs2::sensor subdevice, rs2::stream_profile profile, bool enable_gts, int iter, double &max_diff_system_global_time)
rs2_format format() const
Definition: rs_frame.hpp:44
rs2_timestamp_domain timestamp_domain
rs2_timestamp_domain get_frame_timestamp_domain() const
Definition: rs_frame.hpp:485
GLint GLsizei count
void open(const stream_profile &profile) const
Definition: rs_sensor.hpp:111
REQUIRE_NOTHROW(rs2_log(RS2_LOG_SEVERITY_INFO,"Log message using rs2_log()", nullptr))
int i
void disable_sensitive_options_for(rs2::sensor &sen)
GLuint res
Definition: glext.h:8856
void close() const
Definition: rs_sensor.hpp:173
rs2_format format
unsigned long long get_frame_number() const
Definition: rs_frame.hpp:521
std::vector< stream_profile > get_stream_profiles() const
Definition: rs_sensor.hpp:219
rs2_stream stream_type() const
Definition: rs_frame.hpp:39
void set_option(rs2_option option, float value) const
Definition: rs_options.hpp:99
double get_time()
Definition: rs_internal.hpp:62
int fps() const
Definition: rs_frame.hpp:49
Definition: parser.hpp:150
void start(T callback) const
Definition: rs_sensor.hpp:185
void stop() const
Definition: rs_sensor.hpp:195
CHECK_FALSE(inverse(inverse(p))==p)
rs2_timestamp_domain
Specifies the clock in relation to which the frame timestamp was measured.
Definition: rs_frame.h:19


librealsense2
Author(s): Sergey Dorodnicov , Doron Hirshberg , Mark Horn , Reagan Lopez , Itay Carpis
autogenerated on Mon May 3 2021 02:50:13