algo.cpp
Go to the documentation of this file.
1 // License: Apache 2.0. See LICENSE file in root directory.
2 // Copyright(c) 2015 Intel Corporation. All Rights Reserved.
3 
4 #include "algo.h"
5 #include "option.h"
6 #include "core/video-frame.h"
7 
8 using namespace librealsense;
9 
11 {
12  return is_auto_exposure;
13 }
14 
16 {
17  return mode;
18 }
19 
21 {
22  return rate;
23 }
24 
26 {
27  return step;
28 }
29 
31 {
33 }
34 
36 {
37  mode = value;
38 }
39 
41 {
42  rate = value;
43 }
44 
46 {
47  step = value;
48 }
49 
51  : _gain_option(gain_option), _exposure_option(exposure_option),
52  _auto_exposure_algo(auto_exposure_state),
53  _keep_alive(true), _data_queue(queue_size), _frames_counter(0),
54  _skip_frames(auto_exposure_state.skip_frames)
55 {
56  _exposure_thread = std::make_shared<std::thread>(
57  [this]()
58  {
59  while (_keep_alive)
60  {
61  std::unique_lock<std::mutex> lk(_queue_mtx);
62  _cv.wait(lk, [&] {return (_data_queue.size() || !_keep_alive); });
63 
64  if (!_keep_alive)
65  return;
66 
67  frame_holder f_holder;
68  auto frame_sts = _data_queue.dequeue(&f_holder, RS2_DEFAULT_TIMEOUT);
69 
70  lk.unlock();
71 
72  if (!frame_sts)
73  {
74  LOG_ERROR("After waiting on data_queue signalled there are no frames on queue");
75  continue;
76  }
77  try
78  {
79  auto frame = std::move(f_holder);
80 
81  double values[2] = {};
82 
83  rs2_metadata_type actual_exposure_md;
84  values[0] = frame->find_metadata( RS2_FRAME_METADATA_ACTUAL_EXPOSURE, &actual_exposure_md )
85  ? static_cast< double >( actual_exposure_md )
87  rs2_metadata_type gain_level_md;
89  ? static_cast< double >( gain_level_md )
90  : _gain_option.query();
91 
92  values[0] /= 1000.; // Fisheye exposure value by extension control-
93  // is in units of MicroSeconds, from FW version 5.6.3.0
94 
95  auto exposure_value = static_cast<float>(values[0]);
96  auto gain_value = static_cast<float>(2. + (values[1] - 15.) / 8.);
97 
99  if (sts)
100  {
101  bool modify_exposure, modify_gain;
102  _auto_exposure_algo.modify_exposure(exposure_value, modify_exposure, gain_value, modify_gain);
103 
104  if (modify_exposure)
105  {
106  auto value = exposure_value * 1000.f;
107  if (value < 1)
108  value = 1;
109 
111  }
112 
113  if (modify_gain)
114  {
115  auto value = (gain_value - 2.f) * 8.f + 15.f;
117  }
118  }
119  }
120  catch (const std::exception& ex)
121  {
122  LOG_ERROR("Error during Auto-Exposure loop: " << ex.what());
123  }
124  catch (...)
125  {
126  LOG_ERROR("Unknown error during Auto-Exposure loop!");
127  }
128  }
129  });
130 }
131 
133 {
134  {
135  std::lock_guard<std::mutex> lk(_queue_mtx);
136  _keep_alive = false;
137  }
138  _cv.notify_one();
139  _exposure_thread->join();
140 }
141 
143 {
144  std::lock_guard<std::mutex> lk(_queue_mtx);
147 }
148 
150 {
151  std::lock_guard<std::mutex> lk(_queue_mtx);
153 }
154 
156 {
157 
159  {
160  return;
161  }
162 
163  _frames_counter = 0;
164 
165  {
166  std::lock_guard<std::mutex> lk(_queue_mtx);
167  _data_queue.enqueue(std::move(frame));
168  }
169  _cv.notify_one();
170 }
171 
173  : exposure_step(ae_step_default_value)
174 {
176 }
177 
178 void auto_exposure_algorithm::modify_exposure(float& exposure_value, bool& exp_modified, float& gain_value, bool& gain_modified)
179 {
180  float total_exposure = exposure * gain;
181  LOG_DEBUG("TotalExposure " << total_exposure << ", target_exposure " << target_exposure);
182  if (fabs(target_exposure - total_exposure) > eps)
183  {
184  rounding_mode_type RoundingMode;
185 
186  if (target_exposure > total_exposure)
187  {
188  float target_exposure0 = total_exposure * (1.0f + exposure_step);
189 
190  target_exposure0 = std::min(target_exposure0, target_exposure);
191  increase_exposure_gain(target_exposure0, target_exposure0, exposure, gain);
192  RoundingMode = rounding_mode_type::ceil;
193  LOG_DEBUG(" ModifyExposure: IncreaseExposureGain: ");
194  LOG_DEBUG(" target_exposure0 " << target_exposure0);
195  }
196  else
197  {
198  float target_exposure0 = total_exposure / (1.0f + exposure_step);
199 
200  target_exposure0 = std::max(target_exposure0, target_exposure);
201  decrease_exposure_gain(target_exposure0, target_exposure0, exposure, gain);
202  RoundingMode = rounding_mode_type::floor;
203  LOG_DEBUG(" ModifyExposure: DecreaseExposureGain: ");
204  LOG_DEBUG(" target_exposure0 " << target_exposure0);
205  }
206  LOG_DEBUG(" exposure " << exposure << ", gain " << gain);
207  if (exposure_value != exposure)
208  {
209  exp_modified = true;
210  exposure_value = exposure;
211  exposure_value = exposure_to_value(exposure_value, RoundingMode);
212  LOG_DEBUG("output exposure by algo = " << exposure_value);
213  }
214  if (gain_value != gain)
215  {
216  gain_modified = true;
217  gain_value = gain;
218  LOG_DEBUG("GainModified: gain = " << gain);
219  gain_value = gain_to_value(gain_value, RoundingMode);
220  LOG_DEBUG(" rounded to: " << gain);
221  }
222  }
223 }
224 
226 {
227  region_of_interest image_roi = roi;
228  auto number_of_pixels = (image_roi.max_x - image_roi.min_x + 1)*(image_roi.max_y - image_roi.min_y + 1);
229  if (number_of_pixels == 0)
230  return false; // empty image
231 
232  auto frame = ((video_frame*)image);
233 
234  if (!is_roi_initialized)
235  {
236  auto width = frame->get_width();
237  auto height = frame->get_height();
238  image_roi.min_x = 0;
239  image_roi.min_y = 0;
240  image_roi.max_x = width - 1;
241  image_roi.max_y = height - 1;
242  number_of_pixels = width * height;
243  }
244 
245  std::vector<int> H(256);
246  auto total_weight = number_of_pixels;
247 
248  auto cols = frame->get_width();
249  im_hist((uint8_t*)frame->get_frame_data(), image_roi, frame->get_bpp() / 8 * cols, &H[0]);
250 
251  histogram_metric score = {};
252  histogram_score(H, total_weight, score);
253  // int EffectiveDynamicRange = (score.highlight_limit - score.shadow_limit);
255  float s1 = (score.main_mean - 128.0f) / 255.0f;
256  float s2 = 0;
257 
258  s2 = (score.over_exposure_count - score.under_exposure_count) / (float)total_weight;
259 
260  float s = -0.3f * (s1 + 5.0f * s2);
261  LOG_DEBUG(" AnalyzeImage Score: " << s);
262 
263  if (s > 0)
264  {
265  direction = +1;
267  }
268  else
269  {
270  LOG_DEBUG(" AnalyzeImage: DecreaseExposure");
271  direction = -1;
273  }
274 
275  if (fabs(1.0f - (exposure * gain) / target_exposure) < hysteresis)
276  {
277  LOG_DEBUG(" AnalyzeImage: Don't Modify (Hysteresis): " << target_exposure << " " << exposure * gain);
278  return false;
279  }
280 
282  LOG_DEBUG(" AnalyzeImage: Modify");
283  return true;
284 }
285 
287 {
288  std::lock_guard<std::recursive_mutex> lock(state_mutex);
289 
290  state = options;
291  flicker_cycle = 1000.0f / (state.get_auto_exposure_antiflicker_rate() * 2.0f);
292  exposure_step = state.get_auto_exposure_step();
293 }
294 
296 {
297  std::lock_guard<std::recursive_mutex> lock(state_mutex);
298  roi = ae_roi;
299  is_roi_initialized = true;
300 }
301 
302 void auto_exposure_algorithm::im_hist(const uint8_t* data, const region_of_interest& image_roi, const int rowStep, int h[])
303 {
304  std::lock_guard<std::recursive_mutex> lock(state_mutex);
305 
306  for (int i = 0; i < 256; ++i)
307  h[i] = 0;
308 
309  const uint8_t* rowData = data + (image_roi.min_y * rowStep);
310  for (int i = image_roi.min_y; i < image_roi.max_y; ++i, rowData += rowStep)
311  for (int j = image_roi.min_x; j < image_roi.max_x; j+=state.sample_rate)
312  ++h[rowData[j]];
313 }
314 
315 void auto_exposure_algorithm::increase_exposure_target(float mult, float& target_exposure)
316 {
318 }
320 void auto_exposure_algorithm::decrease_exposure_target(float mult, float& target_exposure)
321 {
322  target_exposure = std::max((exposure * gain) * (1.0f + mult), minimal_exposure * base_gain);
323 }
324 
325 void auto_exposure_algorithm::increase_exposure_gain(const float& target_exposure, const float& target_exposure0, float& exposure, float& gain)
326 {
327  std::lock_guard<std::recursive_mutex> lock(state_mutex);
328 
329  switch ((int)(state.get_auto_exposure_mode()))
330  {
334  }
335 }
336 void auto_exposure_algorithm::decrease_exposure_gain(const float& target_exposure, const float& target_exposure0, float& exposure, float& gain)
337 {
338  std::lock_guard<std::recursive_mutex> lock(state_mutex);
339 
340  switch ((int)(state.get_auto_exposure_mode()))
341  {
345  }
346 }
347 void auto_exposure_algorithm::static_increase_exposure_gain(const float& /*target_exposure*/, const float& target_exposure0, float& exposure, float& gain)
348 {
349  exposure = std::max(minimal_exposure, std::min(target_exposure0 / base_gain, maximal_exposure));
350  gain = std::min(gain_limit, std::max(target_exposure0 / exposure, base_gain));
351 }
352 void auto_exposure_algorithm::static_decrease_exposure_gain(const float& /*target_exposure*/, const float& target_exposure0, float& exposure, float& gain)
353 {
354  exposure = std::max(minimal_exposure, std::min(target_exposure0 / base_gain, maximal_exposure));
355  gain = std::min(gain_limit, std::max(target_exposure0 / exposure, base_gain));
356 }
357 void auto_exposure_algorithm::anti_flicker_increase_exposure_gain(const float& target_exposure, const float& /*target_exposure0*/, float& exposure, float& gain)
358 {
359  std::vector< std::tuple<float, float, float> > exposure_gain_score;
360 
361  for (int i = 1; i < 4; ++i)
362  {
364  {
365  continue;
366  }
367  float exposure1 = std::max(std::min(i * flicker_cycle, maximal_exposure), flicker_cycle);
368  float gain1 = base_gain;
369 
370  if ((exposure1 * gain1) != target_exposure)
371  {
372  gain1 = std::min(std::max(target_exposure / exposure1, base_gain), gain_limit);
373  }
374  float score1 = fabs(target_exposure - exposure1 * gain1);
375  exposure_gain_score.push_back(std::tuple<float, float, float>(score1, exposure1, gain1));
376  }
377 
378  std::sort(exposure_gain_score.begin(), exposure_gain_score.end());
379 
380  exposure = std::get<1>(exposure_gain_score.front());
381  gain = std::get<2>(exposure_gain_score.front());
382 }
383 void auto_exposure_algorithm::anti_flicker_decrease_exposure_gain(const float& target_exposure, const float& /*target_exposure0*/, float& exposure, float& gain)
384 {
385  std::vector< std::tuple<float, float, float> > exposure_gain_score;
386 
387  for (int i = 1; i < 4; ++i)
388  {
390  {
391  continue;
392  }
393  float exposure1 = std::max(std::min(i * flicker_cycle, maximal_exposure), flicker_cycle);
394  float gain1 = base_gain;
395  if ((exposure1 * gain1) != target_exposure)
396  {
397  gain1 = std::min(std::max(target_exposure / exposure1, base_gain), gain_limit);
398  }
399  float score1 = fabs(target_exposure - exposure1 * gain1);
400  exposure_gain_score.push_back(std::tuple<float, float, float>(score1, exposure1, gain1));
401  }
402 
403  std::sort(exposure_gain_score.begin(), exposure_gain_score.end());
404 
405  exposure = std::get<1>(exposure_gain_score.front());
406  gain = std::get<2>(exposure_gain_score.front());
407 }
408 void auto_exposure_algorithm::hybrid_increase_exposure_gain(const float& target_exposure, const float& target_exposure0, float& exposure, float& gain)
409 {
410  if (anti_flicker_mode)
411  {
413  }
414  else
415  {
417  LOG_DEBUG("HybridAutoExposure::IncreaseExposureGain: " << exposure * gain << " " << flicker_cycle * base_gain << " " << base_gain);
418  if (target_exposure > 0.99 * flicker_cycle * base_gain)
419  {
420  anti_flicker_mode = true;
422  LOG_DEBUG("anti_flicker_mode = true");
423  }
424  }
425 }
426 void auto_exposure_algorithm::hybrid_decrease_exposure_gain(const float& target_exposure, const float& target_exposure0, float& exposure, float& gain)
427 {
428  if (anti_flicker_mode)
429  {
430  LOG_DEBUG("HybridAutoExposure::DecreaseExposureGain: " << exposure << " " << flicker_cycle << " " << gain << " " << base_gain);
431  if ((target_exposure) <= 0.99 * (flicker_cycle * base_gain))
432  {
433  anti_flicker_mode = false;
435  LOG_DEBUG("anti_flicker_mode = false");
436  }
437  else
438  {
440  }
441  }
442  else
443  {
445  }
446 }
447 
449 {
450  const float line_period_us = 19.33333333f;
451 
452  float ExposureTimeLine = (exp_ms * 1000.0f / line_period_us);
453  if (rounding_mode == rounding_mode_type::ceil) ExposureTimeLine = std::ceil(ExposureTimeLine);
454  else if (rounding_mode == rounding_mode_type::floor) ExposureTimeLine = std::floor(ExposureTimeLine);
455  else ExposureTimeLine = round(ExposureTimeLine);
456  return ((float)ExposureTimeLine * line_period_us) / 1000.0f;
457 }
458 
460 {
461 
462  if (gain < base_gain) { return base_gain; }
463  else if (gain > 16.0f) { return 16.0f; }
464  else {
465  if (rounding_mode == rounding_mode_type::ceil) return std::ceil(gain * 8.0f) / 8.0f;
466  else if (rounding_mode == rounding_mode_type::floor) return std::floor(gain * 8.0f) / 8.0f;
467  else return round(gain * 8.0f) / 8.0f;
468  }
469 }
470 
471 template <typename T> inline T sqr(const T& x) { return (x*x); }
472 void auto_exposure_algorithm::histogram_score(std::vector<int>& h, const int total_weight, histogram_metric& score)
473 {
474  score.under_exposure_count = 0;
475  score.over_exposure_count = 0;
476 
477  for (size_t i = 0; i <= under_exposure_limit; ++i)
478  {
479  score.under_exposure_count += h[i];
480  }
481  score.shadow_limit = 0;
482  //if (Score.UnderExposureCount < UnderExposureNoiseLimit)
483  {
484  score.shadow_limit = under_exposure_limit;
485  for (size_t i = under_exposure_limit + 1; i <= over_exposure_limit; ++i)
486  {
488  {
489  break;
490  }
491  score.shadow_limit++;
492  }
493  int lower_q = 0;
494  score.lower_q = 0;
495  for (size_t i = under_exposure_limit + 1; i <= over_exposure_limit; ++i)
496  {
497  lower_q += h[i];
498  if (lower_q > total_weight / 4)
499  {
500  break;
501  }
502  score.lower_q++;
503  }
504  }
505 
506  for (size_t i = over_exposure_limit; i <= 255; ++i)
507  {
508  score.over_exposure_count += h[i];
509  }
510 
511  score.highlight_limit = 255;
512  //if (Score.OverExposureCount < OverExposureNoiseLimit)
513  {
514  score.highlight_limit = over_exposure_limit;
515  for (size_t i = over_exposure_limit; i >= under_exposure_limit; --i)
516  {
518  {
519  break;
520  }
521  score.highlight_limit--;
522  }
523  int upper_q = 0;
524  score.upper_q = over_exposure_limit;
525  for (size_t i = over_exposure_limit; i >= under_exposure_limit; --i)
526  {
527  upper_q += h[i];
528  if (upper_q > total_weight / 4)
529  {
530  break;
531  }
532  score.upper_q--;
533  }
534 
535  }
536  int32_t m1 = 0;
537  int64_t m2 = 0;
538 
539  double nn = (double)total_weight - score.under_exposure_count - score.over_exposure_count;
540  if (nn == 0)
541  {
542  nn = (double)total_weight;
543  for (int i = 0; i <= 255; ++i)
544  {
545  m1 += h[i] * i;
546  m2 += static_cast< int64_t >( h[i] ) * sqr( i );
547  }
548  }
549  else
550  {
551  for (int i = under_exposure_limit + 1; i < over_exposure_limit; ++i)
552  {
553  m1 += h[i] * i;
554  m2 += static_cast< int64_t >( h[i] ) * sqr( i );
555  }
556  }
557  score.main_mean = (float)((double)m1 / nn);
558  double Var = (double)m2 / nn - sqr((double)m1 / nn);
559  if (Var > 0)
560  {
561  score.main_std = (float)sqrt(Var);
562  }
563  else
564  {
565  score.main_std = 0.0f;
566  }
567 }
568 
569 rect_gaussian_dots_target_calculator::rect_gaussian_dots_target_calculator(int width, int height, int roi_start_x, int roi_start_y, int roi_width, int roi_height)
570  : _full_width(width), _full_height(height), _roi_start_x(roi_start_x), _roi_start_y(roi_start_y), _width(roi_width), _height(roi_height)
571 {
572  _wt = _width - _tsize;
573  _ht = _height - _tsize;
574  _size = _width * _height;
575 
576  _hwidth = _width >> 1;
577  _hheight = _height >> 1;
578 
579  _imgt.resize(_tsize2);
580  _img.resize(_size);
581  _ncc.resize(_size);
582  memset(_ncc.data(), 0, _size * sizeof(double));
583 
584  _buf.resize(_patch_size);
585 }
586 
588 {
589 }
590 
591 bool rect_gaussian_dots_target_calculator::calculate(const uint8_t* img, float* target_dims, unsigned int target_dims_size)
592 {
593  bool ret = false;
594  if (target_dims_size < 4)
595  return ret;
596 
597  normalize(img);
598  calculate_ncc();
599 
600  if (find_corners())
601  ret = validate_corners(img);
602 
603  if (ret)
604  {
605  if (target_dims_size == 4)
606  calculate_rect_sides(target_dims);
607  else if (target_dims_size == 8)
608  {
609  int j = 0;
610  for (int i = 0; i < 4; ++i)
611  {
612  target_dims[j++] = static_cast<float>(_corners[i].x + _roi_start_x);
613  target_dims[j++] = static_cast<float>(_corners[i].y + _roi_start_y);
614  }
615  }
616  }
617 
618  return ret;
619 }
620 
622 {
623  uint8_t min_val = 255;
624  uint8_t max_val = 0;
625 
626  int jumper = _full_width - _width;
628  for (int j = 0; j < _height; ++j)
629  {
630  for (int i = 0; i < _width; ++i)
631  {
632  if (*p < min_val)
633  min_val = *p;
634 
635  if (*p > max_val)
636  max_val = *p;
637 
638  ++p;
639  }
640 
641  p += jumper;
642  }
643 
644  if (max_val > min_val)
645  {
646  double factor = 1.0 / (max_val - min_val);
647 
648  p = img;
649  double* q = _img.data();
651  for (int j = 0; j < _height; ++j)
652  {
653  for (int i = 0; i < _width; ++i)
654  *q++ = 1.0f - (*p++ - min_val) * factor;
655 
656  p += jumper;
657  }
658  }
659 }
660 
662 {
663  double* pncc = _ncc.data() + (_htsize * _width + _htsize);
664  double* pi = _img.data();
665  double* pit = _imgt.data();
666 
667  const double* pt = nullptr;
668  const double* qi = nullptr;
669 
670  double sum = 0.0;
671  double mean = 0.0;
672  double norm = 0.0;
673 
674  double min_val = 2.0;
675  double max_val = -2.0;
676  double tmp = 0.0;
677 
678  for (int j = 0; j < _ht; ++j)
679  {
680  for (int i = 0; i < _wt; ++i)
681  {
682  qi = pi;
683  sum = 0.0f;
684  for (int m = 0; m < _tsize; ++m)
685  {
686  for (int n = 0; n < _tsize; ++n)
687  sum += *qi++;
688 
689  qi += _wt;
690  }
691 
692  mean = sum / _tsize2;
693 
694  qi = pi;
695  sum = 0.0f;
696  pit = _imgt.data();
697  for (int m = 0; m < _tsize; ++m)
698  {
699  for (int n = 0; n < _tsize; ++n)
700  {
701  *pit = *qi++ - mean;
702  sum += *pit * *pit;
703  ++pit;
704  }
705  qi += _wt;
706  }
707 
708  norm = sqrt(sum);
709 
710  pt = _template.data();
711  pit = _imgt.data();
712  sum = 0.0;
713  for (int k = 0; k < _tsize2; ++k)
714  sum += *pit++ * *pt++;
715 
716  tmp = sum / norm;
717  if (tmp < min_val)
718  min_val = tmp;
719 
720  if (tmp > max_val)
721  max_val = tmp;
722 
723  *pncc++ = tmp;
724  ++pi;
725  }
726 
727  pncc += _tsize;
728  pi += _tsize;
729  }
730 
731  if (max_val > min_val)
732  {
733  double factor = 1.0 / (max_val - min_val);
734  double div = 1.0 - _thresh;
735  pncc = _ncc.data();
736  for (int i = 0; i < _size; ++i)
737  {
738  tmp = (*pncc - min_val) * factor;
739  *pncc++ = (tmp < _thresh ? 0 : (tmp - _thresh) / div);
740  }
741  }
742 }
743 
745 {
746  static const int edge = 20;
747 
748  // upper left
749  _pts[0].x = 0;
750  _pts[0].y = 0;
751  double peak = 0.0f;
752  double* p = _ncc.data() + _htsize * _width;
753  for (int j = _htsize; j < _hheight; ++j)
754  {
755  p += _htsize;
756  for (int i = _htsize; i < _hwidth; ++i)
757  {
758  if (*p > peak)
759  {
760  peak = *p;
761  _pts[0].x = i;
762  _pts[0].y = j;
763  }
764  ++p;
765  }
766  p += _hwidth;
767  }
768 
769  if (peak < _thresh || _pts[0].x < edge || _pts[0].y < edge)
770  return false;
771 
772  // upper right
773  _pts[1].x = 0;
774  _pts[1].y = 0;
775  peak = 0.0f;
776  p = _ncc.data() + (_htsize * _width);
777  for (int j = _htsize; j < _hheight; ++j)
778  {
779  p += _hwidth;
780  for (int i = _hwidth; i < _width - _htsize; ++i)
781  {
782  if (*p > peak)
783  {
784  peak = *p;
785  _pts[1].x = i;
786  _pts[1].y = j;
787  }
788  ++p;
789  }
790  p += _htsize;
791  }
792 
793  if (peak < _thresh || _pts[1].x + edge > _width || _pts[1].y < edge || _pts[1].x - _pts[0].x < edge)
794  return false;
795 
796  // lower left
797  _pts[2].x = 0;
798  _pts[2].y = 0;
799  peak = 0.0f;
800  p = _ncc.data() + (_hheight * _width);
801  for (int j = _hheight; j < _height - _htsize; ++j)
802  {
803  p += _htsize;
804  for (int i = _htsize; i < _hwidth; ++i)
805  {
806  if (*p > peak)
807  {
808  peak = *p;
809  _pts[2].x = i;
810  _pts[2].y = j;
811  }
812  ++p;
813  }
814  p += _hwidth;
815  }
816 
817  if (peak < _thresh || _pts[2].x < edge || _pts[2].y + edge > _height || _pts[2].y - _pts[1].y < edge)
818  return false;
819 
820  // lower right
821  _pts[3].x = 0;
822  _pts[3].y = 0;
823  peak = 0.0f;
824  p = _ncc.data() + (_hheight * _width);
825  for (int j = _hheight; j < _height - _htsize; ++j)
826  {
827  p += _hwidth;
828  for (int i = _hwidth; i < _width - _htsize; ++i)
829  {
830  if (*p > peak)
831  {
832  peak = *p;
833  _pts[3].x = i;
834  _pts[3].y = j;
835  }
836  ++p;
837  }
838  p += _htsize;
839  }
840 
841  if (peak < _thresh || _pts[3].x + edge > _width || _pts[3].y + edge > _height || _pts[3].x - _pts[2].x < edge || _pts[3].y - _pts[1].y < edge)
842  return false;
843  else
844  refine_corners();
845 
846  return true;
847 }
848 
850 {
851  double* f = _buf.data();
852  int hs = _patch_size >> 1;
853 
854  // upper left
855  int pos = (_pts[0].y - hs) * _width + _pts[0].x - hs;
856 
857  _corners[0].x = static_cast<double>(_pts[0].x) - hs;
858  minimize_x(_ncc.data() + pos, _patch_size, f, _corners[0].x);
859 
860  _corners[0].y = static_cast<double>(_pts[0].y) - hs;
861  minimize_y(_ncc.data() + pos, _patch_size, f, _corners[0].y);
862 
863  // upper right
864  pos = (_pts[1].y - hs) * _width + _pts[1].x - hs;
865 
866  _corners[1].x = static_cast<double>(_pts[1].x) - hs;
867  minimize_x(_ncc.data() + pos, _patch_size, f, _corners[1].x);
868 
869  _corners[1].y = static_cast<double>(_pts[1].y) - hs;
870  minimize_y(_ncc.data() + pos, _patch_size, f, _corners[1].y);
871 
872  // lower left
873  pos = (_pts[2].y - hs) * _width + _pts[2].x - hs;
874 
875  _corners[2].x = static_cast<double>(_pts[2].x) - hs;
876  minimize_x(_ncc.data() + pos, _patch_size, f, _corners[2].x);
877 
878  _corners[2].y = static_cast<double>(_pts[2].y) - hs;
879  minimize_y(_ncc.data() + pos, _patch_size, f, _corners[2].y);
880 
881  // lower right
882  pos = (_pts[3].y - hs) * _width + _pts[3].x - hs;
883 
884  _corners[3].x = static_cast<double>(_pts[3].x) - hs;
885  minimize_x(_ncc.data() + pos, _patch_size, f, _corners[3].x);
886 
887  _corners[3].y = static_cast<double>(_pts[3].y) - hs;
888  minimize_y(_ncc.data() + pos, _patch_size, f, _corners[3].y);
889 }
890 
892 {
893  bool ok = true;
894 
895  static const int pos_diff_threshold = 4;
896  if( std::abs( _corners[0].x - _corners[2].x ) > pos_diff_threshold
897  || std::abs( _corners[1].x - _corners[3].x ) > pos_diff_threshold
898  || std::abs( _corners[0].y - _corners[1].y ) > pos_diff_threshold
899  || std::abs( _corners[2].y - _corners[3].y ) > pos_diff_threshold )
900  {
901  ok = false;
902  }
903 
904  return ok;
905 }
906 
908 {
909  double lx = _corners[1].x - _corners[0].x;
910  double ly = _corners[1].y - _corners[0].y;
911  rect_sides[0] = static_cast<float>(sqrt(lx * lx + ly * ly)); // uppper
912 
913  lx = _corners[3].x - _corners[2].x;
914  ly = _corners[3].y - _corners[2].y;
915  rect_sides[1] = static_cast<float>(sqrt(lx * lx + ly * ly)); // lower
916 
917  lx = _corners[2].x - _corners[0].x;
918  ly = _corners[2].y - _corners[0].y;
919  rect_sides[2] = static_cast<float>(sqrt(lx * lx + ly * ly)); // left
920 
921  lx = _corners[3].x - _corners[1].x;
922  ly = _corners[3].y - _corners[1].y;
923  rect_sides[3] = static_cast<float>(sqrt(lx * lx + ly * ly)); // right
924 }
925 
926 void rect_gaussian_dots_target_calculator::minimize_x(const double* p, int s, double* f, double& x)
927 {
928  int ws = _width - s;
929 
930  for (int i = 0; i < s; ++i)
931  f[i] = 0;
932 
933  for (int j = 0; j < s; ++j)
934  {
935  for (int i = 0; i < s; ++i)
936  f[i] += *p++;
937  p += ws;
938  }
939 
940  x += subpixel_agj(f, s);
941 }
942 
943 void rect_gaussian_dots_target_calculator::minimize_y(const double* p, int s, double* f, double& y)
944 {
945  int ws = _width - s;
946 
947  for (int i = 0; i < s; ++i)
948  f[i] = 0;
949 
950  for (int j = 0; j < s; ++j)
951  {
952  for (int i = 0; i < s; ++i)
953  f[j] += *p++;
954  p += ws;
955  }
956 
957  y += subpixel_agj(f, s);
958 }
959 
961 {
962  int mi = 0;
963  double mv = f[mi];
964  for (int i = 1; i < s; ++i)
965  {
966  if (f[i] > mv)
967  {
968  mi = i;
969  mv = f[mi];
970  }
971  }
972 
973  double half_mv = 0.5f * mv;
974 
975  int x_0 = 0;
976  int x_1 = 0;
977  for (int i = 0; i < s; ++i)
978  {
979  if (f[i] > half_mv)
980  {
981  x_1 = i;
982  break;
983  }
984  }
985 
986  double left_mv = 0.0f;
987  if (x_1 > 0)
988  {
989  x_0 = x_1 - 1;
990  left_mv = x_0 + (half_mv - f[x_0]) / (f[x_1] - f[x_0]);
991  }
992  else
993  left_mv = static_cast<double>(0);
994 
995  x_0 = s - 1;
996  for (int i = s - 1; i >= 0; --i)
997  {
998  if (f[i] > half_mv)
999  {
1000  x_0 = i;
1001  break;
1002  }
1003  }
1004 
1005  double right_mv = 0.0f;
1006  if (x_0 == s - 1)
1007  right_mv = static_cast<double>(s) - 1;
1008  else
1009  {
1010  x_1 = x_0 + 1;
1011  right_mv = x_0 + (half_mv - f[x_0]) / (f[x_1] - f[x_0]);
1012  }
1013 
1014  return (left_mv + right_mv) / 2;
1015 }
1016 
1017 // return 1 if target pattern is found and its location is calculated, zero otherwise.
1018 int rect_calculator::extract_target_dims(const rs2_frame* frame_ref, float4& rect_sides)
1019 {
1020  int ret = 0;
1021  rs2_error* e = nullptr;
1022 
1023  //Target dimension array size is predefined. 4 for RS2_CALIB_TARGET_RECT_GAUSSIAN_DOT_VERTICES and 8 for RS2_CALIB_TARGET_POS_GAUSSIAN_DOT_VERTICES.
1024  int dim_size = _roi ? 4 : 8;
1026  rs2_extract_target_dimensions(frame_ref, tgt_type, reinterpret_cast<float*>(&rect_sides), dim_size, &e);
1027  if (e == nullptr)
1028  {
1029  ret = 1;
1030  }
1031 
1032  return ret;
1033 }
librealsense::rect_gaussian_dots_target_calculator::calculate
bool calculate(const uint8_t *img, float *target_dims, unsigned int target_dims_size) override
Definition: algo.cpp:591
librealsense::auto_exposure_modes::auto_exposure_anti_flicker
@ auto_exposure_anti_flicker
librealsense::rect_gaussian_dots_target_calculator::minimize_x
void minimize_x(const double *p, int s, double *f, double &x)
Definition: algo.cpp:926
librealsense
Definition: algo.h:18
RS2_CALIB_TARGET_ROI_RECT_GAUSSIAN_DOT_VERTICES
@ RS2_CALIB_TARGET_ROI_RECT_GAUSSIAN_DOT_VERTICES
Definition: rs_frame.h:87
uint8_t
unsigned char uint8_t
Definition: stdint.h:78
librealsense::rect_gaussian_dots_target_calculator::_ht
int _ht
Definition: algo.h:231
librealsense::auto_exposure_algorithm::gain
float gain
Definition: algo.h:96
librealsense::region_of_interest::max_y
int max_y
Definition: roi.h:17
librealsense::auto_exposure_mechanism::~auto_exposure_mechanism
~auto_exposure_mechanism()
Definition: algo.cpp:132
min
int min(int a, int b)
Definition: lz4s.c:73
test-librs-connections.n
n
Definition: test-librs-connections.py:38
librealsense::auto_exposure_algorithm::static_decrease_exposure_gain
void static_decrease_exposure_gain(const float &target_exposure, const float &target_exposure0, float &exposure, float &gain)
Definition: algo.cpp:352
librealsense::auto_exposure_mechanism::add_frame
void add_frame(frame_holder frame)
Definition: algo.cpp:155
librealsense::rect_gaussian_dots_target_calculator::_height
int _height
Definition: algo.h:227
librealsense::auto_exposure_mechanism::_gain_option
option & _gain_option
Definition: algo.h:130
librealsense::rect_gaussian_dots_target_calculator::_img
std::vector< double > _img
Definition: algo.h:224
librealsense::rect_gaussian_dots_target_calculator::_width
int _width
Definition: algo.h:226
librealsense::rect_gaussian_dots_target_calculator::refine_corners
void refine_corners()
Definition: algo.cpp:849
librealsense::rect_gaussian_dots_target_calculator::_tsize2
const int _tsize2
Definition: algo.h:186
librealsense::rect_gaussian_dots_target_calculator::_buf
std::vector< double > _buf
Definition: algo.h:222
librealsense::region_of_interest
Definition: roi.h:12
librealsense::auto_exposure_algorithm::rounding_mode_type::ceil
@ ceil
librealsense::rect_gaussian_dots_target_calculator::_roi_start_x
int _roi_start_x
Definition: algo.h:245
librealsense::auto_exposure_mechanism::auto_exposure_mechanism
auto_exposure_mechanism(option &gain_option, option &exposure_option, const auto_exposure_state &auto_exposure_state)
Definition: algo.cpp:50
librealsense::rect_gaussian_dots_target_calculator::minimize_y
void minimize_y(const double *p, int s, double *f, double &y)
Definition: algo.cpp:943
librealsense::auto_exposure_state::mode
auto_exposure_modes mode
Definition: algo.h:53
librealsense::auto_exposure_algorithm::hybrid_increase_exposure_gain
void hybrid_increase_exposure_gain(const float &target_exposure, const float &target_exposure0, float &exposure, float &gain)
Definition: algo.cpp:408
librealsense::rect_gaussian_dots_target_calculator::calculate_rect_sides
void calculate_rect_sides(float *rect_sides)
Definition: algo.cpp:907
example1 - object detection.score
score
Definition: example1 - object detection.py:63
librealsense::rect_gaussian_dots_target_calculator::_full_width
int _full_width
Definition: algo.h:247
rsutils::number::float4
Definition: third-party/rsutils/include/rsutils/number/float3.h:47
librealsense::rect_gaussian_dots_target_calculator::_template
const std::vector< double > _template
Definition: algo.h:190
video-frame.h
librealsense::auto_exposure_algorithm::minimal_exposure
float minimal_exposure
Definition: algo.h:95
librealsense::auto_exposure_state::get_auto_exposure_antiflicker_rate
unsigned get_auto_exposure_antiflicker_rate() const
Definition: algo.cpp:20
rs2_frame
struct rs2_frame rs2_frame
Definition: rs_types.h:230
rs2_error
Definition: rs.cpp:227
librealsense::rect_gaussian_dots_target_calculator::_hheight
int _hheight
Definition: algo.h:233
librealsense::auto_exposure_algorithm::exposure_step
std::atomic< float > exposure_step
Definition: algo.h:100
librealsense::rect_gaussian_dots_target_calculator::point::x
T x
Definition: algo.h:238
mode
GLenum mode
Definition: glad/glad/glad.h:1385
pi
static const double pi
Definition: src/types.h:42
q
GLdouble GLdouble GLdouble q
Definition: glad/glad/glad.h:1877
librealsense::auto_exposure_state::set_auto_exposure_step
void set_auto_exposure_step(float value)
Definition: algo.cpp:45
librealsense::auto_exposure_algorithm::rounding_mode_type
rounding_mode_type
Definition: algo.h:69
librealsense::auto_exposure_algorithm::over_exposure_limit
uint8_t over_exposure_limit
Definition: algo.h:97
librealsense::rect_gaussian_dots_target_calculator::validate_corners
bool validate_corners(const uint8_t *img)
Definition: algo.cpp:891
librealsense::auto_exposure_algorithm::hysteresis
float hysteresis
Definition: algo.h:98
LOG_DEBUG
#define LOG_DEBUG(...)
Definition: easyloggingpp.h:70
test-control-reply.s1
s1
Definition: test-control-reply.py:25
mult
float3 mult(const float3x3 &a, const float3 &b)
Definition: test-pose.cpp:69
librealsense::auto_exposure_algorithm::increase_exposure_gain
void increase_exposure_gain(const float &target_exposure, const float &target_exposure0, float &exposure, float &gain)
Definition: algo.cpp:325
librealsense::auto_exposure_algorithm::target_exposure
float target_exposure
Definition: algo.h:96
librealsense::auto_exposure_state
Definition: algo.h:28
H
const int H
Definition: rs-software-device.cpp:16
librealsense::frame_interface
Definition: frame-interface.h:20
RS2_DEFAULT_TIMEOUT
#define RS2_DEFAULT_TIMEOUT
Definition: rs_config.h:13
algo.h
librealsense::rect_gaussian_dots_target_calculator::_hwidth
int _hwidth
Definition: algo.h:232
librealsense::auto_exposure_algorithm::auto_exposure_algorithm
auto_exposure_algorithm(const auto_exposure_state &auto_exposure_state)
Definition: algo.cpp:172
librealsense::auto_exposure_state::set_enable_auto_exposure
void set_enable_auto_exposure(bool value)
Definition: algo.cpp:30
librealsense::rect_gaussian_dots_target_calculator::rect_gaussian_dots_target_calculator
rect_gaussian_dots_target_calculator(int width, int height, int roi_start_x, int roi_start_y, int roi_width, int roi_height)
Definition: algo.cpp:569
librealsense::auto_exposure_algorithm::anti_flicker_decrease_exposure_gain
void anti_flicker_decrease_exposure_gain(const float &target_exposure, const float &target_exposure0, float &exposure, float &gain)
Definition: algo.cpp:383
librealsense::auto_exposure_algorithm::maximal_exposure
float maximal_exposure
Definition: algo.h:95
width
GLint GLsizei width
Definition: glad/glad/glad.h:1397
librealsense::auto_exposure_modes
auto_exposure_modes
Definition: algo.h:22
m
std::mutex m
Definition: test-waiting-on.cpp:126
data
GLboolean * data
Definition: glad/glad/glad.h:1481
librealsense::auto_exposure_mechanism::update_auto_exposure_roi
void update_auto_exposure_roi(const region_of_interest &roi)
Definition: algo.cpp:149
librealsense::rect_gaussian_dots_target_calculator::point::y
T y
Definition: algo.h:239
sqr
T sqr(const T &x)
Definition: algo.cpp:471
librealsense::rect_gaussian_dots_target_calculator::_pts
point< int > _pts[4]
Definition: algo.h:243
librealsense::auto_exposure_algorithm::update_roi
void update_roi(const region_of_interest &ae_roi)
Definition: algo.cpp:295
librealsense::auto_exposure_algorithm::im_hist
void im_hist(const uint8_t *data, const region_of_interest &image_roi, const int rowStep, int h[])
Definition: algo.cpp:302
librealsense::frame::find_metadata
bool find_metadata(rs2_frame_metadata_value, rs2_metadata_type *p_output_value) const override
Definition: frame.cpp:136
librealsense::auto_exposure_algorithm::exposure_to_value
float exposure_to_value(float exp_ms, rounding_mode_type rounding_mode)
Definition: algo.cpp:448
librealsense::auto_exposure_algorithm::gain_to_value
float gain_to_value(float gain, rounding_mode_type rounding_mode)
Definition: algo.cpp:459
opencv_pointcloud_viewer.tmp
tmp
Definition: opencv_pointcloud_viewer.py:325
height
GLint GLsizei GLsizei height
Definition: glad/glad/glad.h:1397
librealsense::auto_exposure_algorithm::base_gain
float base_gain
Definition: algo.h:95
librealsense::auto_exposure_algorithm::increase_exposure_target
void increase_exposure_target(float mult, float &target_exposure)
Definition: algo.cpp:315
librealsense::region_of_interest::max_x
int max_x
Definition: roi.h:16
librealsense::rect_gaussian_dots_target_calculator::~rect_gaussian_dots_target_calculator
virtual ~rect_gaussian_dots_target_calculator()
Definition: algo.cpp:587
librealsense::auto_exposure_mechanism::_exposure_thread
std::shared_ptr< std::thread > _exposure_thread
Definition: algo.h:133
value
GLfloat value
Definition: glad/glad/glad.h:2099
f
GLdouble f
Definition: glad/glad/glad.h:1517
i
int i
Definition: rs-pcl-color.cpp:54
librealsense::rect_gaussian_dots_target_calculator::_size
int _size
Definition: algo.h:228
librealsense::auto_exposure_mechanism::_frames_counter
std::atomic< unsigned > _frames_counter
Definition: algo.h:138
librealsense::_patch_size
const int _patch_size
Definition: algo.h:154
j
GLint j
Definition: glad/glad/glad.h:2165
librealsense::rect_gaussian_dots_target_calculator::_thresh
const double _thresh
Definition: algo.h:221
librealsense::frame_holder
Definition: frame-holder.h:15
rs2_metadata_type
long long rs2_metadata_type
Definition: rs_types.h:272
librealsense::auto_exposure_state::get_auto_exposure_mode
auto_exposure_modes get_auto_exposure_mode() const
Definition: algo.cpp:15
librealsense::auto_exposure_algorithm::gain_limit
float gain_limit
Definition: algo.h:95
librealsense::auto_exposure_mechanism::_cv
std::condition_variable _cv
Definition: algo.h:134
rs2_calib_target_type
rs2_calib_target_type
Calibration target type.
Definition: rs_frame.h:84
librealsense::rect_gaussian_dots_target_calculator::normalize
void normalize(const uint8_t *img)
Definition: algo.cpp:621
librealsense::auto_exposure_algorithm::prev_direction
int prev_direction
Definition: algo.h:98
librealsense::region_of_interest::min_x
int min_x
Definition: roi.h:14
librealsense::auto_exposure_algorithm::decrease_exposure_gain
void decrease_exposure_gain(const float &target_exposure, const float &target_exposure0, float &exposure, float &gain)
Definition: algo.cpp:336
librealsense::rect_gaussian_dots_target_calculator::subpixel_agj
double subpixel_agj(double *f, int s)
Definition: algo.cpp:960
librealsense::rect_gaussian_dots_target_calculator::_wt
int _wt
Definition: algo.h:230
librealsense::auto_exposure_state::step
float step
Definition: algo.h:55
librealsense::auto_exposure_algorithm::sqr
T sqr(const T &x)
Definition: algo.h:91
librealsense::region_of_interest::min_y
int min_y
Definition: roi.h:15
librealsense::auto_exposure_state::rate
unsigned rate
Definition: algo.h:54
librealsense::auto_exposure_state::is_auto_exposure
bool is_auto_exposure
Definition: algo.h:52
librealsense::auto_exposure_state::skip_frames
static const unsigned skip_frames
Definition: algo.h:49
librealsense::auto_exposure_algorithm::hybrid_decrease_exposure_gain
void hybrid_decrease_exposure_gain(const float &target_exposure, const float &target_exposure0, float &exposure, float &gain)
Definition: algo.cpp:426
librealsense::auto_exposure_algorithm::under_exposure_limit
uint8_t under_exposure_limit
Definition: algo.h:97
librealsense::auto_exposure_algorithm::analyze_image
bool analyze_image(const frame_interface *image)
Definition: algo.cpp:225
librealsense::auto_exposure_algorithm::eps
float eps
Definition: algo.h:99
librealsense::auto_exposure_algorithm::is_roi_initialized
bool is_roi_initialized
Definition: algo.h:103
librealsense::video_frame
Definition: video-frame.h:12
librealsense::rect_gaussian_dots_target_calculator::_ncc
std::vector< double > _ncc
Definition: algo.h:225
librealsense::frame
Definition: frame.h:19
librealsense::rect_calculator::extract_target_dims
int extract_target_dims(const rs2_frame *frame_ref, float4 &rect_sides)
Definition: algo.cpp:1018
librealsense::auto_exposure_algorithm::direction
int direction
Definition: algo.h:98
librealsense::auto_exposure_algorithm::roi
region_of_interest roi
Definition: algo.h:102
int64_t
signed __int64 int64_t
Definition: stdint.h:89
librealsense::auto_exposure_mechanism::update_auto_exposure_state
void update_auto_exposure_state(const auto_exposure_state &auto_exposure_state)
Definition: algo.cpp:142
librealsense::rect_gaussian_dots_target_calculator::_roi_start_y
int _roi_start_y
Definition: algo.h:246
librealsense::auto_exposure_algorithm::histogram_metric
Definition: algo.h:68
librealsense::auto_exposure_algorithm::decrease_exposure_target
void decrease_exposure_target(float mult, float &target_exposure)
Definition: algo.cpp:320
librealsense::auto_exposure_state::set_auto_exposure_antiflicker_rate
void set_auto_exposure_antiflicker_rate(unsigned value)
Definition: algo.cpp:40
librealsense::option::set
virtual void set(float value)=0
librealsense::auto_exposure_state::set_auto_exposure_mode
void set_auto_exposure_mode(auto_exposure_modes value)
Definition: algo.cpp:35
librealsense::auto_exposure_algorithm::exposure
float exposure
Definition: algo.h:96
librealsense::rect_gaussian_dots_target_calculator::_corners
point< double > _corners[4]
Definition: algo.h:242
librealsense::auto_exposure_mechanism::_auto_exposure_algo
auto_exposure_algorithm _auto_exposure_algo
Definition: algo.h:132
int32_t
signed int int32_t
Definition: stdint.h:77
RS2_FRAME_METADATA_GAIN_LEVEL
@ RS2_FRAME_METADATA_GAIN_LEVEL
Definition: rs_frame.h:35
p
double p[GRIDW][GRIDH]
Definition: wave.c:109
librealsense::auto_exposure_mechanism::_exposure_option
option & _exposure_option
Definition: algo.h:131
librealsense::option
Definition: option-interface.h:22
librealsense::auto_exposure_modes::auto_exposure_hybrid
@ auto_exposure_hybrid
librealsense::rect_gaussian_dots_target_calculator::_htsize
const int _htsize
Definition: algo.h:185
librealsense::auto_exposure_algorithm::anti_flicker_increase_exposure_gain
void anti_flicker_increase_exposure_gain(const float &target_exposure, const float &target_exposure0, float &exposure, float &gain)
Definition: algo.cpp:357
sort
void sort(sort_type m_sort_type, const std::string &in, const std::string &out)
Definition: rs-rosbag-inspector.cpp:350
librealsense::auto_exposure_algorithm::under_exposure_noise_limit
int under_exposure_noise_limit
Definition: algo.h:97
state
Definition: rs-measure.cpp:80
RS2_FRAME_METADATA_ACTUAL_EXPOSURE
@ RS2_FRAME_METADATA_ACTUAL_EXPOSURE
Definition: rs_frame.h:34
librealsense::auto_exposure_algorithm::histogram_score
void histogram_score(std::vector< int > &h, const int total_weight, histogram_metric &score)
Definition: algo.cpp:472
librealsense::auto_exposure_algorithm::state_mutex
std::recursive_mutex state_mutex
Definition: algo.h:104
librealsense::auto_exposure_algorithm::over_exposure_noise_limit
int over_exposure_noise_limit
Definition: algo.h:97
librealsense::frame::get_frame_data
const uint8_t * get_frame_data() const override
Definition: frame.cpp:155
image
GLenum GLenum GLsizei void * image
Definition: glad/glad/glad.h:3587
librealsense::auto_exposure_mechanism::_keep_alive
std::atomic< bool > _keep_alive
Definition: algo.h:135
librealsense::auto_exposure_algorithm::update_options
void update_options(const auto_exposure_state &options)
Definition: algo.cpp:286
rmse.e
e
Definition: rmse.py:177
librealsense::auto_exposure_algorithm::static_increase_exposure_gain
void static_increase_exposure_gain(const float &target_exposure, const float &target_exposure0, float &exposure, float &gain)
Definition: algo.cpp:347
rs2::textual_icons::lock
static const textual_icon lock
Definition: device-model.h:186
img
GLint void * img
Definition: glad/glad/glad.h:2435
librealsense::auto_exposure_algorithm::anti_flicker_mode
bool anti_flicker_mode
Definition: algo.h:101
librealsense::rect_gaussian_dots_target_calculator::calculate_ncc
void calculate_ncc()
Definition: algo.cpp:661
x
GLdouble x
Definition: glad/glad/glad.h:2279
option.h
librealsense::auto_exposure_mechanism::_skip_frames
std::atomic< unsigned > _skip_frames
Definition: algo.h:139
librealsense::auto_exposure_state::get_auto_exposure_step
float get_auto_exposure_step() const
Definition: algo.cpp:25
librealsense::auto_exposure_modes::static_auto_exposure
@ static_auto_exposure
librealsense::auto_exposure_mechanism::_queue_mtx
std::mutex _queue_mtx
Definition: algo.h:137
direction
direction
Definition: rs-align.cpp:25
test-query-option.s2
s2
Definition: test-query-option.py:33
librealsense::option::query
virtual float query() const =0
librealsense::auto_exposure_algorithm::flicker_cycle
float flicker_cycle
Definition: algo.h:101
ok
@ ok
Definition: lz4.c:1706
librealsense::rect_gaussian_dots_target_calculator::_imgt
std::vector< double > _imgt
Definition: algo.h:187
librealsense::rect_gaussian_dots_target_calculator::find_corners
bool find_corners()
Definition: algo.cpp:744
s
GLdouble s
Definition: glad/glad/glad.h:2441
realdds::topics::notification::device_options::key::options
const std::string options
Definition: test-device-discovery.py:297
librealsense::auto_exposure_mechanism::_data_queue
single_consumer_queue< frame_holder > _data_queue
Definition: algo.h:136
values
GLsizei const GLfloat * values
Definition: glad/glad/glad.h:2180
RS2_CALIB_TARGET_RECT_GAUSSIAN_DOT_VERTICES
@ RS2_CALIB_TARGET_RECT_GAUSSIAN_DOT_VERTICES
Definition: rs_frame.h:86
librealsense::auto_exposure_algorithm::round
float round(float x)
Definition: algo.h:86
librealsense::auto_exposure_state::get_enable_auto_exposure
bool get_enable_auto_exposure() const
Definition: algo.cpp:10
rs2_extract_target_dimensions
void rs2_extract_target_dimensions(const rs2_frame *frame, rs2_calib_target_type calib_type, float *target_dims, unsigned int target_dims_size, rs2_error **error)
Definition: rs.cpp:2863
librealsense::ae_step_default_value
static const float ae_step_default_value
Definition: algo.h:20
librealsense::auto_exposure_algorithm::rounding_mode_type::floor
@ floor
LOG_ERROR
#define LOG_ERROR(...)
Definition: easyloggingpp.h:73
librealsense::rect_gaussian_dots_target_calculator::_tsize
const int _tsize
Definition: algo.h:184
librealsense::auto_exposure_algorithm::modify_exposure
void modify_exposure(float &exposure_value, bool &exp_modified, float &gain_value, bool &gain_modified)
Definition: algo.cpp:178
y
GLint y
Definition: glad/glad/glad.h:1397
sw.h
int h
Definition: sw-dev/sw.py:11
librealsense::rect_calculator::_roi
bool _roi
Definition: algo.h:262


librealsense2
Author(s): LibRealSense ROS Team
autogenerated on Mon Apr 22 2024 02:12:54