50     : _gain_option(gain_option), _exposure_option(exposure_option),
    51       _auto_exposure_algo(auto_exposure_state),
    52       _keep_alive(true), _data_queue(queue_size), _frames_counter(0),
    73                 LOG_ERROR(
"After waiting on data_queue signalled there are no frames on queue");
    90                 auto exposure_value = 
static_cast<float>(values[0]);
    91                 auto gain_value = 
static_cast<float>(2. + (values[1] - 15.) / 8.);
    96                     bool modify_exposure, modify_gain;
   101                         auto value = exposure_value * 1000.f;
   110                         auto value =  (gain_value - 2.f) * 8.
f + 15.
f;
   115             catch (
const std::exception& ex)
   117                 LOG_ERROR(
"Error during Auto-Exposure loop: " << ex.what());
   121                 LOG_ERROR(
"Unknown error during Auto-Exposure loop!");
   183             float target_exposure0 = total_exposure * (1.0f + 
exposure_step);
   188             LOG_DEBUG(
" ModifyExposure: IncreaseExposureGain: ");
   189             LOG_DEBUG(
" target_exposure0 " << target_exposure0);
   193             float target_exposure0 = total_exposure / (1.0f + 
exposure_step);
   198             LOG_DEBUG(
" ModifyExposure: DecreaseExposureGain: ");
   199             LOG_DEBUG(
" target_exposure0 " << target_exposure0);
   207             LOG_DEBUG(
"output exposure by algo = " << exposure_value);
   209         if (gain_value != gain)
   211             gain_modified = 
true;
   213             LOG_DEBUG(
"GainModified: gain = " << gain);
   223     auto number_of_pixels = (image_roi.
max_x - image_roi.
min_x + 1)*(image_roi.
max_y - image_roi.
min_y + 1);
   224     if (number_of_pixels == 0)
   240     std::vector<int> 
H(256);
   241     auto total_weight = number_of_pixels;
   243     auto cols = 
frame->get_width();
   250     float s1 = (score.main_mean - 128.0f) / 255.0
f;
   253     s2 = (score.over_exposure_count - score.under_exposure_count) / (
float)total_weight;
   255     float s = -0.3f * (s1 + 5.0f * s2);
   265         LOG_DEBUG(
" AnalyzeImage: DecreaseExposure");
   301     for (
int i = 0; 
i < 256; ++
i)
   304     const uint8_t* rowData = data + (image_roi.
min_y * rowStep);
   305     for (
int i = image_roi.
min_y; 
i < image_roi.
max_y; ++
i, rowData += rowStep)
   324     switch ((
int)(
state.get_auto_exposure_mode()))
   335     switch ((
int)(
state.get_auto_exposure_mode()))
   354     std::vector< std::tuple<float, float, float> > exposure_gain_score;
   356     for (
int i = 1; 
i < 4; ++
i)
   365         if ((exposure1 * gain1) != target_exposure)
   369         float score1 = fabs(target_exposure - exposure1 * gain1);
   370         exposure_gain_score.push_back(std::tuple<float, float, float>(score1, exposure1, gain1));
   373     std::sort(exposure_gain_score.begin(), exposure_gain_score.end());
   375     exposure = std::get<1>(exposure_gain_score.front());
   376     gain = std::get<2>(exposure_gain_score.front());
   380     std::vector< std::tuple<float, float, float> > exposure_gain_score;
   382     for (
int i = 1; 
i < 4; ++
i)
   390         if ((exposure1 * gain1) != target_exposure)
   394         float score1 = fabs(target_exposure - exposure1 * gain1);
   395         exposure_gain_score.push_back(std::tuple<float, float, float>(score1, exposure1, gain1));
   398     std::sort(exposure_gain_score.begin(), exposure_gain_score.end());
   400     exposure = std::get<1>(exposure_gain_score.front());
   401     gain = std::get<2>(exposure_gain_score.front());
   445     const float line_period_us = 19.33333333f;
   447     float ExposureTimeLine = (exp_ms * 1000.0f / line_period_us);
   450     else ExposureTimeLine = 
round(ExposureTimeLine);
   451     return ((
float)ExposureTimeLine * line_period_us) / 1000.0f;
   458     else if (gain > 16.0
f) { 
return 16.0f; }
   462         else return round(gain * 8.0f) / 8.0f;
   466 template <
typename T> 
inline T sqr(
const T& 
x) { 
return (x*x); }
   493             if (lower_q > total_weight / 4)
   523             if (upper_q > total_weight / 4)
   537         nn = (double)total_weight;
   538         for (
int i = 0; 
i <= 255; ++
i)
   552     score.
main_mean = (float)((
double)m1 / nn);
   553     double Var = (double)m2 / nn - 
sqr((
double)m1 / nn);
   565     : _full_width(width), _full_height(height), _roi_start_x(roi_start_x), _roi_start_y(roi_start_y), _width(roi_width), _height(roi_height)
   577     memset(
_ncc.data(), 0, 
_size * 
sizeof(double));
   589     if (target_dims_size < 4)
   600         if (target_dims_size == 4)
   602         else if (target_dims_size == 8)
   605             for (
int i = 0; 
i < 4; ++
i)
   639     if (max_val > min_val)
   641         double factor = 1.0 / (max_val - min_val);
   644         double* 
q = 
_img.data();
   649                 *q++ = 1.0
f - (*p++ - min_val) * factor;
   660     double* pit = 
_imgt.data();
   662     const double* pt = 
nullptr;
   663     const double* qi = 
nullptr;
   669     double min_val = 2.0;
   670     double max_val = -2.0;
   673     for (
int j = 0; 
j < 
_ht; ++
j)
   675         for (
int i = 0; 
i < 
_wt; ++
i)
   709                 sum += *pit++ * *pt++;
   726     if (max_val > min_val)
   728         double factor = 1.0 / (max_val - min_val);
   733             tmp = (*pncc - min_val) * factor;
   741     static const int edge = 20;
   846     double* 
f = 
_buf.data();
   890     static const int pos_diff_threshold = 4;
   906     rect_sides[0] = 
static_cast<float>(sqrt(lx * lx + ly * ly)); 
   910     rect_sides[1] = 
static_cast<float>(sqrt(lx * lx + ly * ly)); 
   914     rect_sides[2] = 
static_cast<float>(sqrt(lx * lx + ly * ly)); 
   918     rect_sides[3] = 
static_cast<float>(sqrt(lx * lx + ly * ly)); 
   925     for (
int i = 0; 
i < 
s; ++
i)
   928     for (
int j = 0; 
j < 
s; ++
j)
   930         for (
int i = 0; 
i < 
s; ++
i)
   942     for (
int i = 0; 
i < 
s; ++
i)
   945     for (
int j = 0; 
j < 
s; ++
j)
   947         for (
int i = 0; 
i < 
s; ++
i)
   959     for (
int i = 1; 
i < 
s; ++
i)
   968     double half_mv = 0.5f * mv;
   972     for (
int i = 0; 
i < 
s; ++
i)
   981     double left_mv = 0.0f;
   985         left_mv = x_0 + (half_mv - f[x_0]) / (f[x_1] - f[x_0]);
   988         left_mv = 
static_cast<double>(0);
   991     for (
int i = s - 1; 
i >= 0; --
i)
  1000     double right_mv = 0.0f;
  1002         right_mv = 
static_cast<double>(
s) - 1;
  1006         right_mv = x_0 + (half_mv - f[x_0]) / (f[x_1] - f[x_0]);
  1009     return (left_mv + right_mv) / 2;
  1019     int dim_size = _roi ? 4 : 8;
 static const textual_icon lock
bool supports_frame_metadata(const rs2_frame_metadata_value &frame_metadata) const override
std::shared_ptr< std::thread > _exposure_thread
std::vector< double > _ncc
float3 mult(const float3x3 &a, const float3 &b)
void set_enable_auto_exposure(bool value)
rect_gaussian_dots_target_calculator(int width, int height, int roi_start_x, int roi_start_y, int roi_width, int roi_height)
void hybrid_decrease_exposure_gain(const float &target_exposure, const float &target_exposure0, float &exposure, float &gain)
std::vector< double > _imgt
std::atomic< unsigned > _frames_counter
unsigned get_auto_exposure_antiflicker_rate() const
static const unsigned skip_frames
bool analyze_image(const frame_interface *image)
int extract_target_dims(const rs2_frame *frame_ref, float4 &rect_sides)
std::recursive_mutex state_mutex
point< double > _corners[4]
const std::vector< double > _template
float exposure_to_value(float exp_ms, rounding_mode_type rounding_mode)
void update_auto_exposure_state(const auto_exposure_state &auto_exposure_state)
void increase_exposure_target(float mult, float &target_exposure)
void calculate_rect_sides(float *rect_sides)
virtual void set(float value)=0
static const float ae_step_default_value
rs2_calib_target_type
Calibration target type. 
void static_increase_exposure_gain(const float &target_exposure, const float &target_exposure0, float &exposure, float &gain)
std::atomic< float > exposure_step
void set_auto_exposure_mode(auto_exposure_modes value)
bool validate_corners(const uint8_t *img)
auto_exposure_algorithm _auto_exposure_algo
virtual float query() const =0
void minimize_y(const double *p, int s, double *f, double &y)
void sort(sort_type m_sort_type, const std::string &in, const std::string &out)
void add_frame(frame_holder frame)
double subpixel_agj(double *f, int s)
std::atomic< bool > _keep_alive
void anti_flicker_increase_exposure_gain(const float &target_exposure, const float &target_exposure0, float &exposure, float &gain)
GLenum GLenum GLsizei void * image
void set_auto_exposure_antiflicker_rate(unsigned value)
~auto_exposure_mechanism()
int over_exposure_noise_limit
std::atomic< unsigned > _skip_frames
bool calculate(const uint8_t *img, float *target_dims, unsigned int target_dims_size) override
void update_options(const auto_exposure_state &options)
void static_decrease_exposure_gain(const float &target_exposure, const float &target_exposure0, float &exposure, float &gain)
void set_auto_exposure_step(float value)
int under_exposure_noise_limit
option & _exposure_option
float gain_to_value(float gain, rounding_mode_type rounding_mode)
GLint GLsizei GLsizei height
void increase_exposure_gain(const float &target_exposure, const float &target_exposure0, float &exposure, float &gain)
auto_exposure_modes get_auto_exposure_mode() const
auto_exposure_mechanism(option &gain_option, option &exposure_option, const auto_exposure_state &auto_exposure_state)
#define RS2_DEFAULT_TIMEOUT
void normalize(const uint8_t *img)
auto_exposure_algorithm(const auto_exposure_state &auto_exposure_state)
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)
uint8_t under_exposure_limit
std::vector< double > _img
single_consumer_queue< frame_holder > _data_queue
virtual ~rect_gaussian_dots_target_calculator()
GLsizei const GLfloat * values
void hybrid_increase_exposure_gain(const float &target_exposure, const float &target_exposure0, float &exposure, float &gain)
GLdouble GLdouble GLdouble q
void anti_flicker_decrease_exposure_gain(const float &target_exposure, const float &target_exposure0, float &exposure, float &gain)
void decrease_exposure_target(float mult, float &target_exposure)
uint8_t over_exposure_limit
float get_auto_exposure_step() const
typename ::boost::move_detail::remove_reference< T >::type && move(T &&t) BOOST_NOEXCEPT
bool get_enable_auto_exposure() const
void update_roi(const region_of_interest &ae_roi)
void histogram_score(std::vector< int > &h, const int total_weight, histogram_metric &score)
std::vector< double > _buf
const byte * get_frame_data() const override
void modify_exposure(float &exposure_value, bool &exp_modified, float &gain_value, bool &gain_modified)
void update_auto_exposure_roi(const region_of_interest &roi)
void decrease_exposure_gain(const float &target_exposure, const float &target_exposure0, float &exposure, float &gain)
void minimize_x(const double *p, int s, double *f, double &x)
rs2_metadata_type get_frame_metadata(const rs2_frame_metadata_value &frame_metadata) const override
struct rs2_frame rs2_frame
std::condition_variable _cv
void im_hist(const uint8_t *data, const region_of_interest &image_roi, const int rowStep, int h[])